diff --git a/.gitignore b/.gitignore index 9a786e95..f1522d25 100644 --- a/.gitignore +++ b/.gitignore @@ -30,3 +30,8 @@ data/vavam-driver/* # uv.lock is only used in local development. On the server, we use uv tool run, # which does not require uv.lock. **/uv.lock + +# local dir +my_run/ +outputs/ +logs/ diff --git a/pyproject.toml b/pyproject.toml index 2732f597..b9a8e34c 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -17,6 +17,7 @@ members = [ "src/physics", "src/tools", "src/driver", + "src/render", ] # This is a hacky workaround to skip installing flash attention diff --git a/src/grpc/alpasim_grpc/v0/sensorsim.proto b/src/grpc/alpasim_grpc/v0/sensorsim.proto index d4184ef5..7568989c 100644 --- a/src/grpc/alpasim_grpc/v0/sensorsim.proto +++ b/src/grpc/alpasim_grpc/v0/sensorsim.proto @@ -188,7 +188,18 @@ message RGBRenderRequest { fixed64 frame_start_us = 5; fixed64 frame_end_us = 6; - PosePair sensor_pose = 7; + // Deprecated: Use ego_pose instead. sensor_pose is camera pose in world frame. + // Kept for backward compatibility. If ego_pose is provided, it will be used instead. + PosePair sensor_pose = 7 [deprecated = true]; + + // Ego vehicle pose in world frame (preferred for MTGS renderer) + // If provided, this will be used instead of deriving from sensor_pose + PosePair ego_pose = 13; + + // Rig to camera transformation (camera pose relative to ego/rig frame) + // If provided, this will be used for accurate camera2ego transformation + // If not provided, will be loaded from asset folder or data_source + common.Pose rig_to_camera = 14; repeated DynamicObject dynamic_objects = 8; diff --git a/src/render/__init__.py b/src/render/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/src/render/base_renderer.py b/src/render/base_renderer.py new file mode 100644 index 00000000..e6cb9523 --- /dev/null +++ b/src/render/base_renderer.py @@ -0,0 +1,49 @@ +from abc import ABC +from dataclasses import dataclass, field +from functools import cached_property +from typing import Dict, List, Optional, Tuple, Type, Union, Any +from typing_extensions import Literal + +import torch +from torch.nn import Module, Parameter + + +class RenderState(dict): + CAMERAS = "cameras" + LIDAR = "lidar" + AGENT_STATE = "agent_state" # {object_id: np.ndarray([x, y, heading])} + TIMESTAMP = "timestamp" + + +class BaseRenderer(ABC): + + def __init__( + self, + device: str = "cuda" if torch.cuda.is_available() else "cpu", + ): + self.device = device + self.__from_scratch__() + + def __from_scratch__(self): + self.sensors = None + + def _check_for_reliance(self): + if self.background_asset is None: + raise ValueError("No background asset set for renderer.") + + def reset(self): + self.__from_scratch__() + + @property + def background_asset(self): + return None + + def set_asset(self, asset): + pass + + def render(self, render_state: RenderState): + pass + + def physical_world(self, agent_state): + # [x, y, heading] + raise NotImplementedError \ No newline at end of file diff --git a/src/render/pyproject.toml b/src/render/pyproject.toml new file mode 100644 index 00000000..5777bbad --- /dev/null +++ b/src/render/pyproject.toml @@ -0,0 +1,41 @@ +[build-system] +requires = ["setuptools>=61.0"] +build-backend = "setuptools.build_meta" + +[project] +name = "alpasim_render" +version = "0.1.0" +description = "DigitalTwin renderer module for Alpasim" +requires-python = ">=3.11,<3.12" +dependencies = [ + "torch>=2.0.0", + "numpy>=1.24.0", + "opencv-python>=4.8.0", + "pyquaternion>=0.9.0", + "gsplat>=1.0.0", + "alpasim_utils", # For geometry_utils and other utilities +] + +authors = [ + {name = "Alpasim Team"}, +] + +[tool.uv.sources] +alpasim_utils = {workspace = true} + +# Note: render module uses 'src.render' and 'src.utils' import path structure +# The module structure is: +# - src/render/base_renderer.py -> src.render.base_renderer +# - src/render/src/digitaltwin.py -> src.render.src.digitaltwin +# - src/render/src/utils/ -> src.utils (gaussian_utils, portable_utils) +# - src/render/src/gaussian_model/ -> src.gaussian_model + +# Package discovery configuration +# render module has a special structure where: +# - base_renderer.py is at the root of render/ +# - src/ subdirectory contains the main code +# - src/utils/ contains utilities that are imported as src.utils.* +[tool.setuptools.packages.find] +where = ["."] +include = ["src*"] +exclude = ["tests*", "*.tests*"] diff --git a/src/render/src/__init__.py b/src/render/src/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/src/render/src/gaussian_model/__init__.py b/src/render/src/gaussian_model/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/src/render/src/gaussian_model/rigid_object.py b/src/render/src/gaussian_model/rigid_object.py new file mode 100644 index 00000000..0b7d7b89 --- /dev/null +++ b/src/render/src/gaussian_model/rigid_object.py @@ -0,0 +1,152 @@ +import logging + +import torch +from torch.nn import Parameter, Module +try: + from gsplat.cuda._wrapper import spherical_harmonics +except ImportError: + print("Please install gsplat>=1.0.0") + +from ..utils.gaussian_utils import quat_mult, quat_to_rotmat, interpolate_quats, IDFT +from .vanilla_gaussian_splatting import VanillaPortableGaussianModel +logger = logging.getLogger(__name__) + +class RigidPortableSubModel(VanillaPortableGaussianModel): + """Portable Gaussian Splatting model + + Args: + asset: portable Gaussian Model with config include + - type + - sh_degree + - scale_dim + - fourier_features_dim + - fourier_features_scale + - fourier_in_space + - log_timestamps + """ + MODEL_TYPE = "rigid" + + def __init__(self, **kwargs): + self.log_replay = kwargs.get("log_replay", False) + super().__init__(**kwargs) + # TODO + # self.visible_range = kwargs.get("visible_range", None) + + def _update_default_config(self, config): + config = super()._update_default_config(config) + config["fourier_features_dim"] = config.get("fourier_features_dim", None) + config["fourier_features_scale"] = config.get("fourier_features_scale", 1.0) + config["fourier_in_space"] = config.get("fourier_in_space", 'temporal') + config["log_timestamps"] = config.get("log_timestamps", None) + return config + + def load_state_dict(self, dict: dict): + super().load_state_dict(dict) + self.exist_log = ('instance_trans' in dict.keys()) + if self.exist_log: + self.log_trans = Parameter(dict['instance_trans'].squeeze()) + self.log_quats = Parameter(dict['instance_quats'].squeeze()) + self.static_in_log = (self.log_trans.dim() == 1) + if not self.static_in_log: + assert getattr(self.config, "log_timestamps", None) is not None + self.log_start_time = self.config.log_timestamps.min().item() + self.log_timestamps = self.config.log_timestamps.squeeze() - self.log_start_time + + # TODO: + # maybe make some transition trajectories at the beginning and the ending to avoid sudden appearance or disappearance + + log_type = "static" if self.static_in_log else "dynamic" + logger.debug(f"Log pose for `{self.model_name_abbr}` loaded. LOG TYPE: `{log_type}`") + if self.log_replay: + logger.debug(f"Log replay for `{self.model_name_abbr}` enabled.") + + def set_static_force(self): + self.static_in_log = True + in_frame_mask = self.log_trans[:, 2] < 1000 + self.log_trans = Parameter(self.log_trans[in_frame_mask][0]) + self.log_quats = Parameter(self.log_quats[in_frame_mask][0]) + + def get_means(self, global_quat, global_trans): + local_means = self.gauss_params['means'] + rot_cur_frame = quat_to_rotmat(global_quat[None, ...])[0, ...] + self.global_means = local_means @ rot_cur_frame.T + global_trans + return self.global_means + + def get_quats(self, global_quat, global_trans=None): + local_quats = self.quats / self.quats.norm(dim=-1, keepdim=True) + global_quats = quat_mult(global_quat[None, ...], local_quats) + return global_quats + + def get_fourier_features(self, x): + scaled_x = x * self.config.fourier_features_scale + input_is_normalized = (self.config.fourier_in_space == 'temporal') + idft_base = IDFT(scaled_x, self.config.fourier_features_dim, input_is_normalized).to(self.device) + return torch.sum(self.features_dc * idft_base[..., None], dim=1, keepdim=False) + + def get_true_features_dc(self, timestamp=None, cam_obj_yaw=None): + if self.config.fourier_features_dim is None: + return self.features_dc + normalized_x = timestamp if self.config.fourier_in_space == 'temporal' else cam_obj_yaw + assert normalized_x is not None + return self.get_fourier_features(normalized_x) + + def get_gaussian_rgbs(self, camera_to_worlds, timestamp, device=None): + device = device if device is not None else self.device + assert device != torch.device("cpu"), "`sphereical_harmonics` in `gsplat` only supports CUDA" + true_features_dc = self.get_true_features_dc(timestamp, None) + colors = torch.cat((true_features_dc[:, None, :], self.features_rest), dim=1).to(device) + if self.sh_degree > 0: + viewdirs = self.global_means.detach().to(device) - camera_to_worlds[..., :3, 3].to(device) # (N, 3) + viewdirs = viewdirs / viewdirs.norm(dim=-1, keepdim=True) + rgbs = spherical_harmonics(self.sh_degree, viewdirs, colors) + rgbs = torch.clamp(rgbs + 0.5, 0.0, 1.0) + else: + rgbs = torch.sigmoid(colors[:, 0, :]) + + return rgbs + + def get_opacity(self): + return torch.sigmoid(self.gauss_params['opacities']).squeeze(-1) + + def _get_log_pose_from_timestamp(self, timestamp): + self.log_timestamps = self.log_timestamps.to(self.device) + relative_timestamp = timestamp - self.log_start_time + + diffs = relative_timestamp - self.log_timestamps + prev_frame = torch.argmin(torch.where(diffs >= 0, diffs, float('inf'))) + next_frame = torch.argmin(torch.where(diffs <= 0, -diffs, float('inf'))) + + if next_frame == prev_frame: + # Timestamp exactly matches a frame, no interpolation needed + return self.log_quats[next_frame], self.log_trans[next_frame], timestamp + + # Calculate interpolation factor + t = (relative_timestamp - self.log_timestamps[prev_frame]) / (self.log_timestamps[next_frame] - self.log_timestamps[prev_frame]) + + # Interpolate quaternions (using slerp) and translations + quat_interp = interpolate_quats(self.log_quats[prev_frame], self.log_quats[next_frame], t).squeeze() + trans_interp = torch.lerp(self.log_trans[prev_frame], self.log_trans[next_frame], t) + + return quat_interp, trans_interp, timestamp + + def _decide_global_pose(self, quat=None, trans=None, timestamp=None): + if self.static_in_log: + return self.log_quats, self.log_trans, timestamp + if quat is not None and trans is not None: + assert quat.shape == (4,) and trans.shape == (3,) + return quat.float(), trans.float(), timestamp + return self._get_log_pose_from_timestamp(timestamp) + + def get_global_gaussians(self, quat=None, trans=None, timestamp=None, **kwargs): + quat, trans, timestamp = self._decide_global_pose( + quat=quat, + trans=trans, + timestamp=timestamp, + ) + + return { + "means": self.get_means(global_trans=trans, global_quat=quat), + "scales": self.get_scales(), + "quats": self.get_quats(global_trans=trans, global_quat=quat), + "opacities": self.get_opacity(), + } diff --git a/src/render/src/gaussian_model/rigid_object_mirrored.py b/src/render/src/gaussian_model/rigid_object_mirrored.py new file mode 100644 index 00000000..846920f9 --- /dev/null +++ b/src/render/src/gaussian_model/rigid_object_mirrored.py @@ -0,0 +1,83 @@ +import torch +try: + from gsplat.cuda._wrapper import spherical_harmonics +except ImportError: + print("Please install gsplat>=1.0.0") + +from ..utils.gaussian_utils import quat_mult, quat_to_rotmat +from .rigid_object import RigidPortableSubModel + + +def flip_spherical_harmonics(coeff): + """ + Flip the spherical harmonics coefficients along the y-axis. + + Args: + coeff (torch.Tensor): A tensor of shape [N, 16, 3], where N is the number of Gaussians, + 16 is the number of spherical harmonics coefficients (up to degree l=3), + and 3 is the feature dimension. + + Returns: + torch.Tensor: The flipped spherical harmonics coefficients. + """ + # Indices corresponding to m < 0 for l up to 3 + indices_m_negative = [1, 4, 5, 9, 10, 11] + + # Create a flip factor tensor of ones and minus ones + flip_factors = torch.ones(coeff.shape[1], device=coeff.device) + flip_factors[indices_m_negative] = -1 + + # Reshape flip_factors to [1, 16, 1] for broadcasting + flip_factors = flip_factors.view(1, -1, 1) + + # Apply the flip factors to the coefficients + flipped_coeff = coeff * flip_factors + + return flipped_coeff + + +class MirroredRigidPortableSubModel(RigidPortableSubModel): + MODEL_TYPE = "mirrored" + + def get_means(self, global_quat, global_trans): + local_means: torch.Tensor = self.gauss_params['means'] + local_means = local_means.unsqueeze(0).repeat(2, 1, 1) + local_means[1, :, :] = local_means[1, :, :] * local_means.new_tensor([1, -1, 1]).view(1, 3) # flip y + local_means = local_means.view(-1, 3) + + rot_cur_frame = quat_to_rotmat(global_quat[None, ...])[0, ...] + self.global_means = local_means @ rot_cur_frame.T + global_trans + return self.global_means + + def get_quats(self, global_quat, global_trans=None): + local_quats = self.quats / self.quats.norm(dim=-1, keepdim=True) + local_quats = local_quats.unsqueeze(0).repeat(2, 1, 1) + local_quats[1, :, :] = local_quats[1, :, :] * local_quats.new_tensor([1, -1, 1, -1]).view(1, 4) # flip quats at y axis + local_quats = local_quats.view(-1, 4) + + global_quats = quat_mult(global_quat[None, ...], local_quats) + return global_quats + + def get_scales(self): + return torch.exp(self.scales).repeat(2, 1) + + def get_gaussian_rgbs(self, camera_to_worlds, timestamp, device=None): + device = device if device is not None else self.device + assert device != torch.device("cpu"), "`sphereical_harmonics` in `gsplat` only supports CUDA" + true_features_dc = self.get_true_features_dc(timestamp, None) + colors = torch.cat((true_features_dc[:, None, :], self.features_rest), dim=1).to(device) + colors = colors.unsqueeze(0).repeat(2, 1, 1, 1) + colors[1, ...] = flip_spherical_harmonics(colors[1, ...]) + colors = colors.view(-1, 16, 3) + if self.sh_degree > 0: + viewdirs = self.global_means.detach().to(device) - camera_to_worlds[..., :3, 3].to(device) # (C, N, 3) + viewdirs = viewdirs / viewdirs.norm(dim=-1, keepdim=True) + rgbs = spherical_harmonics(self.sh_degree, viewdirs, colors) + rgbs = torch.clamp(rgbs + 0.5, 0.0, 1.0) + else: + rgbs = torch.sigmoid(colors[:, 0, :]) + + return rgbs + + def get_opacity(self): + return torch.sigmoid(self.gauss_params['opacities']).squeeze(-1).repeat(2) diff --git a/src/render/src/gaussian_model/vanilla_gaussian_splatting.py b/src/render/src/gaussian_model/vanilla_gaussian_splatting.py new file mode 100644 index 00000000..336a41fe --- /dev/null +++ b/src/render/src/gaussian_model/vanilla_gaussian_splatting.py @@ -0,0 +1,175 @@ +from typing import Dict, List, Optional, Tuple, Type, Union, Any + +import numpy as np +import torch +from torch.nn import Parameter, Module + +try: + from gsplat.cuda._wrapper import spherical_harmonics +except ImportError: + print("Please install gsplat>=1.0.0") + +class VanillaPortableGaussianModel(torch.nn.Module): + """Portable Gaussian Splatting model + + Args: + asset: portable Gaussian Model with config include + - type + - sh_degree + - scale_dim + """ + MODEL_TYPE = "vanilla" + + def __init__( + self, + asset: Any, + model_name: Optional[str] = None, + **kwargs, + ): + super().__init__() + self.eval() + self.model_type = self.MODEL_TYPE + self.model_name = model_name + self.config = self._update_default_config(asset.config) + self._init_gauss_params() + self.load_state_dict(asset.state_dict) + + def _update_default_config(self, config): + config["sh_degree"] = config.get("sh_degree", None) + config["scale_dim"] = config.get("scale_dim", 3) + return config + + def _init_gauss_params(self): + self.gauss_params = torch.nn.ParameterDict({ + "means": None, + "scales": None, + "quats": None, + "features_dc": None, + "features_rest": None, + "opacities": None, + }) + + def load_state_dict(self, dict: dict): + for name in self.gauss_params.keys(): + if "gauss_params" in dict: + self.gauss_params[name] = Parameter(dict["gauss_params"][name]) + else: + self.gauss_params[name] = Parameter(dict[f"gauss_params.{name}"]) + + def get_isotropic_quats(self, num_points): + quats = torch.zeros(num_points, 4) + quats[:, 0] = 1.0 + return quats.to(self.device) + + @property + def device(self): + return self.gauss_params["means"].device + + @property + def sh_degree(self): + return self.config.sh_degree + + @property + def num_points(self): + return self.means.shape[0] + + @property + def means(self) -> torch.nn.Parameter: + return self.gauss_params["means"] + + @property + def scales(self) -> torch.nn.Parameter: + if self.config.scale_dim == 3: + return self.gauss_params["scales"] + elif self.config.scale_dim == 1: + return self.gauss_params["scales"].repeat(1, 3) + + @property + def quats(self) -> torch.nn.Parameter: + if self.config.scale_dim == 3: + return self.gauss_params["quats"] + elif self.config.scale_dim == 1: + return self.get_isotropic_quats(self.num_points) + + @property + def features_dc(self) -> torch.nn.Parameter: + return self.gauss_params["features_dc"] + + @property + def features_rest(self) -> torch.nn.Parameter: + return self.gauss_params["features_rest"] + + @property + def opacities(self) -> torch.nn.Parameter: + return self.gauss_params["opacities"] + + @property + def model_name_abbr(self): + return self.model_name.split("_")[-1] + + def get_means(self): + return self.gauss_params['means'] + + def get_scales(self): + return torch.exp(self.scales) + + def get_quats(self): + quats = self.quats + return quats / quats.norm(dim=-1, keepdim=True) + + def get_opacity(self): + return torch.sigmoid(self.gauss_params['opacities']).squeeze(-1) + + def get_gaussian_rgbs(self, camera_to_worlds, device=None, **kwargs): + device = device if device is not None else self.device + assert device != torch.device("cpu"), "`sphereical_harmonics` in `gsplat` only supports CUDA" + assert self.features_dc.dim() == 2, \ + "if Fourier embedding is used in models derived from `VanillaPortableGaussianModel`, a new `get_gaussian_rgbs` function must be implemented" + colors = torch.cat((self.features_dc[:, None, :], self.features_rest), dim=1).to(device) + if self.sh_degree > 0: + viewdirs = self.means.detach().to(device) - camera_to_worlds[..., :3, 3].to(device) # (N, 3) + viewdirs = viewdirs / viewdirs.norm(dim=-1, keepdim=True) + rgbs = spherical_harmonics(self.sh_degree, viewdirs, colors) + rgbs = torch.clamp(rgbs + 0.5, 0.0, 1.0) + else: + rgbs = torch.sigmoid(colors[:, 0, :]) + + return rgbs + + def get_global_gaussians(self, **kwargs): + + return { + "means": self.get_means(), + "scales": self.get_scales(), + "quats": self.get_quats(), + "opacities": self.get_opacity(), + } + + def get_gaussian_params(self, **kwargs): + raise ValueError("Should not be called.") + + def get_gaussian_param_groups(self) -> Dict[str, List[Parameter]]: + raise ValueError("Should not be called.") + + def get_param_groups(self) -> Dict[str, List[Parameter]]: + raise ValueError("Should not be called.") + + def k_nearest_sklearn(self, x: torch.Tensor, k: int): + """ + Find k-nearest neighbors using sklearn's NearestNeighbors. + x: The data tensor of shape [num_samples, num_features] + k: The number of neighbors to retrieve + """ + # Convert tensor to numpy array + x_np = x.cpu().numpy() + + # Build the nearest neighbors model + from sklearn.neighbors import NearestNeighbors + + nn_model = NearestNeighbors(n_neighbors=k + 1, algorithm="auto", metric="euclidean").fit(x_np) + + # Find the k-nearest neighbors + distances, indices = nn_model.kneighbors(x_np) + + # Exclude the point itself from the result and return + return distances[:, 1:].astype(np.float32), indices[:, 1:].astype(np.float32) \ No newline at end of file diff --git a/src/render/src/mtgs.py b/src/render/src/mtgs.py new file mode 100644 index 00000000..d8afd4b9 --- /dev/null +++ b/src/render/src/mtgs.py @@ -0,0 +1,583 @@ +from __future__ import annotations +import logging +from dataclasses import dataclass, field +from functools import cached_property +from typing import Dict, List, Optional, Tuple, Type, Union, Any +from typing_extensions import Literal +from pathlib import Path + +import numpy as np +import cv2 +from pyquaternion import Quaternion +import torch + +try: + from gsplat.rendering import rasterization +except ImportError: + print("Please install gsplat>=1.0.0") + +from src.utils.alpasim_utils.geometry_utils import Sim2 +from src.render.base_renderer import BaseRenderer, RenderState +from src.render.src.utils.gaussian_utils import matrix_to_quaternion, quat_to_rotmat, quat_to_angle +from src.render.src.utils.portable_utils import convert_to_attribute_dict, AttrDict +from src.render.src.gaussian_model.vanilla_gaussian_splatting import VanillaPortableGaussianModel as VanillaModel +from src.render.src.gaussian_model.rigid_object import RigidPortableSubModel as RigidModel +from src.render.src.gaussian_model.rigid_object_mirrored import MirroredRigidPortableSubModel as MirroredModel + +logger = logging.getLogger(__name__) + +MODEL_MAPPING = { + "VanillaGaussianSplattingModel": VanillaModel, + "SkyboxGaussianSplattingModel": VanillaModel, + "RigidSubModel": RigidModel, + "MirroredRigidSubModel": MirroredModel, + "DeformableSubModel": None, +} + +def auto_submodel(atom_asset): + if not isinstance(atom_asset, AttrDict): + atom_asset = convert_to_attribute_dict(atom_asset) + original_model_type = atom_asset.config.type + return MODEL_MAPPING[original_model_type] + + +class MTGS(BaseRenderer): + def __init__( + self, + *args, + asset_folder_path: Union[str, Path], + enable_collider: bool = False, + render_depth: bool = False, + rasterize_mode: Literal["classic", "antialiased"] = "classic", + radius_clip: float = 0., + background_color: Union[Literal["random", "black", "white"], Tuple] = "black", + **kwargs + ): + super().__init__(*args, **kwargs) + self.enable_collider = enable_collider + self.render_depth = render_depth + self.rasterize_mode = rasterize_mode + self.radius_clip = radius_clip + self.bg_color = self._init_background_color(background_color) + self.asset_manager = MTGSAssetManager(Path(asset_folder_path), self.device) + self.sensor_caches = None + self.world_to_nre = None + + def _init_background_color(self, background_color): + if isinstance(background_color, str): + if background_color == "random": + background = torch.rand(3, device=self.device) + elif background_color == "white": + background = torch.ones(3, device=self.device) + elif background_color == "black": + background = torch.zeros(3, device=self.device) + else: + raise ValueError(f"Unknown background color {background_color}") + return background + elif isinstance(background_color, tuple): + assert len(background_color) == 3 + for color in background_color: + assert 0 <= color <= 255 + return torch.tensor(background_color, device=self.device).float() / 255. + + @property + def background_color(self) -> torch.Tensor: + return self.bg_color.to(self.device) + + def _prepare_metas(self): + self.model_types = {} + self.node_types = {} + self.submodel_names = {} + self.timestamp = None + self.sensor_mapping = {} + + def _init_gaussian_models(self): + if hasattr(self, "gaussian_models"): + del self.gaussian_models + torch.cuda.empty_cache() + self.gaussian_models = torch.nn.ParameterDict() + + @cached_property + def background_asset(self): + return self.gaussian_models["background"] + + @property + def num_submodels(self): + return len(self.node_types.keys()) + + @property + def num_cameras(self): + return len(self.sensor_mapping.keys()) + + def reset(self, current_scene_id, asset_id: Optional[str] = None, **kwargs): + """ + Reset the renderer for a new scene. + + Args: + current_scene_id: Scene ID + asset_id: Optional asset ID. If None, uses current_scene_id + """ + # Use provided asset_id or fall back to scene_id + if asset_id is None: + asset_id = current_scene_id + + reset_asset = self.asset_manager.reset(asset_id) + if reset_asset: + self._prepare_metas() + self._init_gaussian_models() + self.set_asset(self.asset_manager.background_asset_dict) + # Note: calibrate_agent_state now requires ego2globals to be passed explicitly + # This will be called separately with the required data + self.sensor_caches = None + + # Reset world_to_nre when changing scenes + self.world_to_nre = None + + # Mark as initialized for this scene + self._scene_id = current_scene_id + self._initialized = True + logger.info(f"Renderer reset completed for scene {current_scene_id} (asset: {asset_id})") + + def set_world_to_nre(self, world_to_nre: np.ndarray): + self.world_to_nre = world_to_nre + logger.info(f"Set world_to_nre transformation: translation={world_to_nre[:3, 3]}") + + def calibrate_agent_state(self, ego2globals: Optional[torch.Tensor] = None): + """ + Get the agent states in the reconstruction. + + Args: + ego2globals: Optional array/tensor of shape [N, 4, 4] containing ego-to-global transformation matrices. + Can be numpy array or torch.Tensor. If None, will try to extract from loaded gaussian models. + + Returns: + Dictionary mapping agent IDs to their states (translation and rotation) + """ + mtgs_agent2states = {} + + # Handle ego state from ego2globals if provided + if ego2globals is not None: + # Convert to torch tensor if it's a numpy array + if isinstance(ego2globals, np.ndarray): + ego2globals_tensor = torch.tensor(ego2globals, dtype=torch.float64, device=self.device) + else: + # Already a torch tensor, just ensure correct dtype and device + ego2globals_tensor = ego2globals.to(dtype=torch.float64, device=self.device) + + if ego2globals_tensor.ndim == 2: + ego2globals_tensor = ego2globals_tensor.unsqueeze(0) # Add batch dimension if needed + + # Extract translation and rotation from ego2globals + # Directly use them without any transformation (matching WorldEngine's behavior) + mtgs_ego2globals_trans = ego2globals_tensor[:, :3, 3] + mtgs_ego2globals_quat = matrix_to_quaternion(ego2globals_tensor[:, :3, :3]) + + mtgs_agent2states['ego'] = { + 'translation': mtgs_ego2globals_trans, + 'rotation': mtgs_ego2globals_quat, + } + + # Extract agent states from loaded gaussian models + for asset_token, model_name in self.submodel_names.items(): + if self.node_types[asset_token] != 'na': + continue + + if self.gaussian_models[model_name].static_in_log: + continue + + in_frame_mask = self.gaussian_models[model_name].log_trans[:, 2] < 1000 + + mtgs_agent2states[asset_token] = { + 'translation': self.gaussian_models[model_name].log_trans[in_frame_mask].double(), + 'rotation': self.gaussian_models[model_name].log_quats[in_frame_mask].double(), + } + return mtgs_agent2states + + def get_submodel_name(self, token): + node_type = self.node_types[token] + if len(node_type) > 3: + return token + model_type = self.model_types[token] + return f"{node_type}_{model_type}_{token}" + + def set_asset(self, asset): + is_background = ("background" in asset.keys()) + if is_background: + self.recon2global_translation = asset['background']['config']['recon2world_translation'] + + asset_type = "background" if is_background else "foreground" + for asset_name in asset.keys(): + logger.debug(f"Loading {asset_type} asset <{asset_name}>...") + sub_asset = convert_to_attribute_dict(asset[asset_name]) + asset_class = auto_submodel(sub_asset) + asset_token = asset_name.split("_")[-1] + if asset_token in ["background", "skybox"]: + self.node_types[asset_token] = asset_token + else: + self.node_types[asset_token] = "na" if is_background else "ia" + # short for `native agent` and `inserted agent` respectively + + self.model_types[asset_token] = asset_class.MODEL_TYPE + model_name = self.get_submodel_name(asset_token) + self.submodel_names[asset_token] = model_name + self.gaussian_models[model_name] = asset_class( + asset=sub_asset, + model_name=model_name + ) + + @staticmethod + def get_transform_matrix(rotation, translation): + if not isinstance(rotation, np.ndarray): + rotation = rotation.cpu().numpy() + if not isinstance(translation, np.ndarray): + translation = translation.cpu().numpy() + if rotation.ndim == 1: + # is quaternion + rotation = Quaternion(rotation).rotation_matrix + if translation.ndim == 1: + # change to column vector + translation = np.expand_dims(translation, axis=-1) + if rotation.ndim == 2: + rotation = np.expand_dims(rotation, axis=0) + translation = np.expand_dims(translation, axis=0) + + transform = np.tile(np.eye(4), (rotation.shape[0], 1, 1)) + transform[:, :3, :3] = rotation + transform[:, :3, 3:4] = translation + return torch.from_numpy(transform).float() + + def set_sensors(self, sensors, ego2global): + if self.sensor_caches is not None: + camera_to_egos, intrinsics, map_inverse_distorts, hw_dict = self.sensor_caches + camera_to_worlds = torch.einsum("ij,bjk->bik", ego2global, camera_to_egos) + return camera_to_worlds, intrinsics, map_inverse_distorts, hw_dict + + self.sensor_mapping = {} + sensor2egos = [] + intrinsics = [] + map_inverse_distorts = [] + height, width = None, None + for idx, (cam_name, cam_info) in enumerate(sensors.items()): + self.sensor_mapping[cam_name] = idx + sensor2ego = self.get_transform_matrix( + rotation=cam_info["sensor2ego_rotation"], + translation=cam_info["sensor2ego_translation"] + ).squeeze().to(self.device) # 4 x 4 + + intrinsic = np.array(cam_info["intrinsic"]) + distortion = np.array(cam_info["distortion"]) + new_intrinsic, roi = cv2.getOptimalNewCameraMatrix( + intrinsic, distortion, (cam_info["width"], cam_info["height"]), 1 + ) + map_inverse_distort = cv2.initInverseRectificationMap( + intrinsic, distortion, None, new_intrinsic, (cam_info["width"], cam_info["height"]), cv2.CV_32FC1 + ) + + intrinsic_torch = torch.from_numpy(new_intrinsic).float().to(self.device).squeeze() + sensor2egos.append(sensor2ego) + intrinsics.append(intrinsic_torch) + map_inverse_distorts.append(map_inverse_distort) + + assert (height is None) or (height == cam_info["height"]), "inconsistent height among RGB cameras" + assert (width is None) or (width == cam_info["width"]), "inconsistent width among RGB cameras" + height, width = cam_info["height"], cam_info["width"] + + sensor2egos = torch.stack(sensor2egos, dim=0) # C x 4 x 4 + intrinsics = torch.stack(intrinsics, dim=0) # C x 3 x 3 + height = height if isinstance(height, int) else height.item() + width = width if isinstance(width, int) else width.item() + self.sensor_caches = (sensor2egos, intrinsics, map_inverse_distorts, {"height": height, "width": width}) + + camera_to_worlds = torch.einsum("ij,bjk->bik", ego2global, sensor2egos) + return camera_to_worlds, intrinsics, map_inverse_distorts, {"height": height, "width": width} + + def update_world(self, timestamp, agent_states): + + if (self.timestamp == timestamp and + hasattr(self, "collected_gaussians") and + self.collected_gaussians and + 'means' in self.collected_gaussians): + return + gs_dict = { + "means": [], + "scales": [], + "quats": [], + "opacities": [], + } + for asset_token in self.node_types.keys(): + gaussian_model = self.gaussian_models[self.submodel_names[asset_token]] + if asset_token in agent_states.keys(): + quat, trans = self.get_agent_pose(asset_token, agent_states[asset_token]) + else: + quat, trans = None, None # use original log (for background, skybox, etc.) + + try: + gs = gaussian_model.get_global_gaussians( + quat=quat, + trans=trans, + timestamp=timestamp, + ) + if gs is None: + logger.warning(f"get_global_gaussians returned None for {asset_token}") + continue + for k in gs_dict.keys(): + gs_dict[k].append(gs[k].to(self.device)) + except Exception as e: + logger.error(f"Error collecting gaussians for {asset_token}: {e}", exc_info=True) + raise + + # Check if any gaussians were collected + if not gs_dict["means"]: + logger.error(f"No gaussians collected in update_world! node_types: {list(self.node_types.keys())}, agent_states: {list(agent_states.keys())}, timestamp={timestamp}") + raise RuntimeError(f"No gaussians collected - no models available for timestamp {timestamp}") + + try: + new_collected_gaussians = {} + for key, value in gs_dict.items(): + new_collected_gaussians[key] = torch.cat(value, dim=0) + self.collected_gaussians = new_collected_gaussians + self.timestamp = timestamp + except Exception as e: + logger.error(f"Failed to merge gaussians: {e}", exc_info=True) + raise + + def update_gaussian_rgbs(self, camera_to_worlds): + rgb_list = [] + for asset_token in self.node_types.keys(): + gaussian_model = self.gaussian_models[self.submodel_names[asset_token]] + rgbs = [] + for i in range(camera_to_worlds.shape[0]): + rgbs.append(gaussian_model.get_gaussian_rgbs( + camera_to_worlds=camera_to_worlds[i:i+1], + timestamp=self.timestamp, + device=self.device + ).unsqueeze(0) + ) + rgbs = torch.cat(rgbs, dim=0) # C x ni x 3 + rgb_list.append(rgbs) + if torch.isnan(rgbs).any() or torch.isinf(rgbs).any(): + print(f"NaN or inf in rgbs for model {self.submodel_names[asset_token]}") + + self.collected_gaussians['rgbs'] = torch.cat(rgb_list, dim=1) # C x N x 3 + + @torch.no_grad() + def render(self, render_state: RenderState): + timestamp = render_state[RenderState.TIMESTAMP] + agent_states = render_state[RenderState.AGENT_STATE] # Simulator Local (Ego rear-axis) + + converted_agent_states = {} + for agent_id, agent_state in agent_states.items(): + agent_state_np = np.array(agent_state, dtype=np.float64) + + # Step 1: Simulator Local → Nuplan Global + if self.local2global_translation_xy is not None: + agent_state_np[:2] += self.local2global_translation_xy + + # Step 2: Nuplan Global → Reconstruction Local + if isinstance(self.recon2global_translation, torch.Tensor): + recon2global_xy = self.recon2global_translation[:2].cpu().numpy() + else: + recon2global_xy = np.array(self.recon2global_translation[:2]) + agent_state_np[:2] -= recon2global_xy + + converted_agent_states[agent_id] = agent_state_np + + self.update_world( + timestamp=timestamp, + agent_states=converted_agent_states, + ) + ego2global_raw = self.get_agent_pose('ego', converted_agent_states['ego'], return_matrix=True) + ego2global = ego2global_raw.to(device=self.device, dtype=torch.float32) + + cameras = render_state[RenderState.CAMERAS] + camera_to_worlds, INTRINSICS, map_inverse_distorts, SHAPE = self.set_sensors( + sensors=cameras, + ego2global=ego2global, + ) + self.update_gaussian_rgbs(camera_to_worlds) + + # shift the camera to center of scene looking at center + R = camera_to_worlds[:, :3, :3] # C x 3 x 3 + T = camera_to_worlds[:, :3, 3:4] # C x 3 x 1 + # analytic matrix inverse to get world2camera matrix + R_inv = R.transpose(1,2) # C x 3 x 3 + T_inv = -R_inv @ T + viewmat = self.get_transform_matrix( + rotation=R_inv, + translation=T_inv + ).to(self.device) # C x 4 x 4 + + if self.render_depth: + render_mode = "RGB+ED" + else: + render_mode = "RGB" + + BLOCK_WIDTH = 16 # this controls the tile size of rasterization, 16 is a good default + render, alpha, _ = rasterization( + means=self.collected_gaussians['means'], + quats=self.collected_gaussians['quats'], + scales=self.collected_gaussians['scales'], + opacities=self.collected_gaussians['opacities'], + colors=self.collected_gaussians['rgbs'], + viewmats=viewmat, # [C, 4, 4] + Ks=INTRINSICS.cuda(), # [C, 3, 3] + width=SHAPE['width'], + height=SHAPE['height'], + tile_size=BLOCK_WIDTH, + packed=False, + near_plane=0.01, + far_plane=1e10, + render_mode=render_mode, + sparse_grad=False, + absgrad=True, + rasterize_mode=self.rasterize_mode, + # set some threshold to disregrad small gaussians for faster rendering. + radius_clip=self.radius_clip, + ) + alpha = alpha[:, ...] + rgb = render[:, ..., :3] + (1 - alpha) * self.background_color + rgb = torch.clamp(rgb, 0.0, 1.0) + rgb = rgb.cpu().numpy() * 255 + rgb = rgb.astype(np.uint8) + rgb = [cv2.cvtColor(rgb[i], cv2.COLOR_RGB2BGR) for i in range(rgb.shape[0])] + + outputs = {"image": rgb} + if render_mode == "RGB+ED": + depth_im = render[:, ..., 3:4] + depth_im = torch.where(alpha > 0, depth_im, depth_im.detach().max()) + outputs["depth"] = depth_im.cpu().numpy() + + sensor_dict = {} + for cam_name, cam_idx in self.sensor_mapping.items(): + sensor_dict[cam_name] = {} + for image_key in outputs.keys(): + sensor_dict[cam_name][image_key] = cv2.remap( + outputs[image_key][cam_idx], + map_inverse_distorts[cam_idx][0], + map_inverse_distorts[cam_idx][1], cv2.INTER_LINEAR) + return_dict = { + 'cameras': sensor_dict, + 'lidars': {} # LiDAR rendering is not supported + } + + ego2global_nuplan = ego2global_raw.cpu().numpy() + ego2global_nuplan[:3, 3] = ego2global_nuplan[:3, 3] + self.recon2global_translation[:3] + + meta_data_dict = { + 'ego2global': ego2global_nuplan, + 'render_state': render_state + } + return_dict.update(meta_data_dict) + return return_dict + + def get_agent_pose(self, name, agent_state, return_matrix=False): + if name not in self.mtgs_agent2states.keys(): + return None if return_matrix else (None, None) + + mtgs_agent_state = self.mtgs_agent2states[name] + + agent_state_xy = torch.tensor(agent_state[:2], device=self.device, dtype=torch.float64) + agent_state_heading = torch.tensor(agent_state[-1], device=self.device, dtype=torch.float64) + + nearsest_idx = torch.argmin(torch.norm(mtgs_agent_state['translation'][:, :2] - agent_state_xy, dim=-1)) + log_trans = mtgs_agent_state['translation'][nearsest_idx] + log_quat = mtgs_agent_state['rotation'][nearsest_idx] + + log_rot_matrix = quat_to_rotmat(log_quat) + log_rot_yaw = quat_to_angle(log_quat, focus="yaw")["yaw"] + heading_diff = agent_state_heading - log_rot_yaw + cos_vals = torch.cos(heading_diff) + sin_vals = torch.sin(heading_diff) + rot_matrix_diff = torch.zeros(3, 3, device=self.device, dtype=torch.float64) + rot_matrix_diff[0, 0] = cos_vals + rot_matrix_diff[0, 1] = -sin_vals + rot_matrix_diff[1, 0] = sin_vals + rot_matrix_diff[1, 1] = cos_vals + rot_matrix_diff[2, 2] = 1.0 + + new_trans = log_trans.clone() + new_trans[:2] = agent_state_xy + new_rot_matrix = rot_matrix_diff @ log_rot_matrix + + if return_matrix: + agent2global = torch.zeros(4, 4, device=self.device, dtype=torch.float64) + agent2global[:3, :3] = new_rot_matrix + agent2global[:3, 3] = new_trans + return agent2global + else: + quat = matrix_to_quaternion(new_rot_matrix) + trans = new_trans + return quat, trans + + @property + def local2global_translation_xy(self) -> Optional[np.ndarray]: + if self.world_to_nre is None: + return None + return -self.world_to_nre[:2, 3] + + +class MTGSAssetManager: + + def __init__(self, asset_folder_path: Path, device: torch.device): + self.asset_folder_path = asset_folder_path + self.current_asset_id = None + self.device = device + + def reset(self, asset_id: str): + if asset_id[-4:].startswith('-'): # Check if ends with pattern like "-001" + asset_id = asset_id[:-4] # Remove the suffix + + if self.current_asset_id == asset_id: + return False + + # Clean up old assets + if getattr(self, "background_asset_dict", None) is not None: + del self.background_asset_dict + self.background_asset_dict = None + torch.cuda.empty_cache() + + self.current_asset_id = asset_id + self.load_asset() + return True + + def load_asset(self): + """ + Folder structure: + {asset_dir} + ├── background + ├── road_height_map + └── video_scene_dict.pkl (contains ego2global, etc.) + """ + self.asset_dir = Path(self.asset_folder_path) / self.current_asset_id + logger.info(f"Loading assets from asset {self.current_asset_id}...") + # load background asset (includes background, skybox, and rigid objects) + background_asset_path = self.asset_dir / 'background' / f'{self.current_asset_id}.ckpt' + self.background_asset_dict = torch.load(background_asset_path, map_location=self.device) + logger.info(f"Loaded background asset dict with {len(self.background_asset_dict)} models") + + road_height_map_path = self.asset_dir / 'road_height_map' + self.road_height_map = dict( + map = np.load(road_height_map_path / 'road_height_map.npy'), + sim2 = Sim2.from_json(road_height_map_path / 'sim2.json') + ) + + # Load video_scene_dict_final.pkl if available (contains ego2global, etc.) + video_scene_dict_path = self.asset_dir / 'video_scene_dict.pkl' + self.video_scene_dict = None + if video_scene_dict_path.exists(): + try: + import pickle + with open(video_scene_dict_path, 'rb') as f: + self.video_scene_dict = pickle.load(f) + logger.info(f"Loaded video_scene_dict from {video_scene_dict_path}") + except Exception as e: + logger.warning(f"Failed to load video_scene_dict.pkl: {e}") + + # TODO: load foreground assets. + self.foreground_asset_dir = self.asset_dir / 'foreground' + self.foreground_assets = list(self.foreground_asset_dir.glob('*.ckpt')) + + +# Backward compatibility aliases +DigitalTwin = MTGS +DigitalTwinAssetManager = MTGSAssetManager diff --git a/src/render/src/utils/gaussian_utils.py b/src/render/src/utils/gaussian_utils.py new file mode 100644 index 00000000..e3a0f42a --- /dev/null +++ b/src/render/src/utils/gaussian_utils.py @@ -0,0 +1,172 @@ +import math +import torch + +@torch.jit.script +def quat_to_rotmat(quat: torch.Tensor) -> torch.Tensor: + assert quat.shape[-1] == 4, f"Expected quaternion shape [..., 4], got {quat.shape}" + w, x, y, z = torch.unbind(quat, dim=-1) + + xx = x * x + yy = y * y + zz = z * z + xy = x * y + xz = x * z + yz = y * z + wx = w * x + wy = w * y + wz = w * z + + m00 = 1.0 - 2.0 * (yy + zz) + m01 = 2.0 * (xy - wz) + m02 = 2.0 * (xz + wy) + m10 = 2.0 * (xy + wz) + m11 = 1.0 - 2.0 * (xx + zz) + m12 = 2.0 * (yz - wx) + m20 = 2.0 * (xz - wy) + m21 = 2.0 * (yz + wx) + m22 = 1.0 - 2.0 * (xx + yy) + + mat = torch.stack([m00, m01, m02, m10, m11, m12, m20, m21, m22], dim=-1) + return mat.reshape(quat.shape[:-1] + (3, 3)) + +@torch.jit.script +def quat_mult(q1, q2): + # NOTE: + # Q1 is the quaternion that rotates the vector from the original position to the final position + # Q2 is the quaternion that been rotated + w1, x1, y1, z1 = torch.unbind(q1, dim=-1) + w2, x2, y2, z2 = torch.unbind(q2, dim=-1) + w = w1 * w2 - x1 * x2 - y1 * y2 - z1 * z2 + x = w1 * x2 + x1 * w2 + y1 * z2 - z1 * y2 + y = w1 * y2 - x1 * z2 + y1 * w2 + z1 * x2 + z = w1 * z2 + x1 * y2 - y1 * x2 + z1 * w2 + return torch.stack([w, x, y, z], dim=-1) + +def interpolate_quats(q1, q2, fraction=0.5): + """ + Interpolate between two quaternions using spherical linear interpolation (slerp). + """ + if q1.dim() == 1: + q1 = q1[None, ...] + if q2.dim() == 1: + q2 = q2[None, ...] + + q1 = q1 / torch.norm(q1, dim=-1, keepdim=True) + q2 = q2 / torch.norm(q2, dim=-1, keepdim=True) + + dot = (q1 * q2).sum(dim=-1, keepdim=True) + dot = torch.clamp(dot, -1, 1) + + q2 = torch.where(dot < 0, -q2, q2) + dot = torch.abs(dot) + + similar_mask = dot > 0.9995 + q_interp_similar = q1 + fraction * (q2 - q1) + + theta_0 = torch.acos(dot) + theta = theta_0 * fraction + sin_theta = torch.sin(theta) + sin_theta_0 = torch.sin(theta_0) + s1 = torch.cos(theta) - dot * sin_theta / sin_theta_0 + s2 = sin_theta / sin_theta_0 + q_interp = (s1[..., None] * q1) + (s2[..., None] * q2) + + final_q_interp = torch.zeros_like(q1) + final_q_interp = torch.where(similar_mask, q_interp_similar, q_interp) + final_q_interp = final_q_interp / torch.norm(final_q_interp, dim=-1, keepdim=True) + return final_q_interp + +def IDFT(time, dim, input_normalized=True): + """ + Computes the inverse discrete Fourier transform of a given time signal. + """ + if isinstance(time, float): + time = torch.tensor(time) + t = time.view(-1, 1) + idft = torch.zeros(t.shape[0], dim, dtype=t.dtype, device=t.device) + indices = torch.arange(dim, dtype=torch.int, device=t.device) + even_indices = indices[::2] + odd_indices = indices[1::2] + if input_normalized: + idft[:, even_indices] = torch.cos(t * even_indices * 2 * math.pi / dim) + idft[:, odd_indices] = torch.sin(t * (odd_indices + 1) * 2 * math.pi / dim) + else: + idft[:, even_indices] = torch.cos(t * even_indices) + idft[:, odd_indices] = torch.sin(t * (odd_indices + 1)) + return idft + +def quat_to_angle(quat, focus="yaw"): + # quat: [N, 4] + focus = [focus] if isinstance(focus, str) else focus + w, x, y, z = torch.unbind(quat, dim=-1) + return_dict = dict() + if "yaw" in focus: + return_dict["yaw"] = torch.atan2(2 * (w * z + x * y), 1 - 2 * (y**2 + z**2)) + if "pitch" in focus: + return_dict["pitch"] = torch.asin(2 * (w * y - z * x)) + if "roll" in focus: + return_dict["roll"] = torch.atan2(2 * (w * x + y * z), 1 - 2 * (x**2 + y**2)) + return return_dict + +def angle_to_quat(yaw, pitch, roll): + # yaw, pitch, roll: [N] + cy = torch.cos(yaw / 2) + sy = torch.sin(yaw / 2) + cp = torch.cos(pitch / 2) + sp = torch.sin(pitch / 2) + cr = torch.cos(roll / 2) + sr = torch.sin(roll / 2) + w = cy * cp * cr + sy * sp * sr + x = cy * cp * sr - sy * sp * cr + y = sy * cp * sr + cy * sp * cr + z = sy * cp * cr - cy * sp * sr + return torch.stack([w, x, y, z], dim=-1) + +def matrix_to_quaternion(rotation_matrix): + """ + Convert a 3x3 rotation matrix to a unit quaternion. + """ + if rotation_matrix.dim() == 2: + rotation_matrix = rotation_matrix[None, ...] + assert rotation_matrix.shape[1:] == (3, 3) + + # Compute traces manually instead of using vmap (for compatibility) + traces = rotation_matrix[:, 0, 0] + rotation_matrix[:, 1, 1] + rotation_matrix[:, 2, 2] + quaternion = torch.zeros( + rotation_matrix.shape[0], + 4, + dtype=rotation_matrix.dtype, + device=rotation_matrix.device, + ) + for i in range(rotation_matrix.shape[0]): + matrix = rotation_matrix[i] + trace = traces[i] + if trace > 0: + S = torch.sqrt(trace + 1.0) * 2 + w = 0.25 * S + x = (matrix[2, 1] - matrix[1, 2]) / S + y = (matrix[0, 2] - matrix[2, 0]) / S + z = (matrix[1, 0] - matrix[0, 1]) / S + elif (matrix[0, 0] > matrix[1, 1]) and (matrix[0, 0] > matrix[2, 2]): + S = torch.sqrt(1.0 + matrix[0, 0] - matrix[1, 1] - matrix[2, 2]) * 2 + w = (matrix[2, 1] - matrix[1, 2]) / S + x = 0.25 * S + y = (matrix[0, 1] + matrix[1, 0]) / S + z = (matrix[0, 2] + matrix[2, 0]) / S + elif matrix[1, 1] > matrix[2, 2]: + S = torch.sqrt(1.0 + matrix[1, 1] - matrix[0, 0] - matrix[2, 2]) * 2 + w = (matrix[0, 2] - matrix[2, 0]) / S + x = (matrix[0, 1] + matrix[1, 0]) / S + y = 0.25 * S + z = (matrix[1, 2] + matrix[2, 1]) / S + else: + S = torch.sqrt(1.0 + matrix[2, 2] - matrix[0, 0] - matrix[1, 1]) * 2 + w = (matrix[1, 0] - matrix[0, 1]) / S + x = (matrix[0, 2] + matrix[2, 0]) / S + y = (matrix[1, 2] + matrix[2, 1]) / S + z = 0.25 * S + + quaternion[i] = torch.tensor( + [w, x, y, z], dtype=matrix.dtype, device=matrix.device + ) + return quaternion.squeeze() diff --git a/src/render/src/utils/geometry_utils.py b/src/render/src/utils/geometry_utils.py new file mode 100644 index 00000000..6174c74a --- /dev/null +++ b/src/render/src/utils/geometry_utils.py @@ -0,0 +1,147 @@ +import numpy as np +from pyquaternion import Quaternion +from scipy.optimize import minimize +import torch + +from src.utils.alpasim_utils.geometry_utils import Sim2 + +def get_road_plane_from_traj(positions, weights): + """ + Get the road plane from the trajectory. + Args: + positions: [N, 3] tensor. The trajectory positions. + weight: the weight for the optimization. + Returns: + road_plane: [3] tensor, [a, b, c]. The road plane, z = ax + by + c + """ + z = positions[:, -1] + x = positions[:, :-1] + + def objective(params): + ones = torch.ones(x.shape[0], 1) + x_hat = torch.cat([x, ones], dim=1) + z_pred = params * x_hat + + dist_cost = torch.mean(weights * (z - z_pred)**2) + return dist_cost + + init_params = torch.ones(positions.shape[1]) + init_params[-1] = z.min() + result = minimize(objective, init_params, method='Nelder-Mead') + return result.x + +def get_raster_values_at_coords( + points_xy: np.ndarray, sim2: Sim2, np_image: np.ndarray, fill_value=np.nan +): + # Note: we do NOT round here, because we need to enforce scaled discretization. + city_coords = points_xy[:, :2] + + npyimage_coords = sim2.transform_from(city_coords) + npyimage_coords = npyimage_coords.astype(np.int64) + + # out of bounds values will default to the fill value, and will not be indexed into the array. + # index in at (x,y) locations, which are (y,x) in the image + raster_values = np.full((npyimage_coords.shape[0]), fill_value) + # generate boolean array indicating whether the value at each index represents a valid coordinate. + ind_valid_pts = ( + (npyimage_coords[:, 1] >= 0) + * (npyimage_coords[:, 1] < np_image.shape[0]) + * (npyimage_coords[:, 0] >= 0) + * (npyimage_coords[:, 0] < np_image.shape[1]) + ) + raster_values[ind_valid_pts] = np_image[ + npyimage_coords[ind_valid_pts, 1], npyimage_coords[ind_valid_pts, 0] + ] + return raster_values + +def calculate_box_eular_angle_and_z( + height_map: np.ndarray, sim2: Sim2, box: np.ndarray +): + if box.ndim == 1: + assert box.shape[0] == 6 + box = box.reshape(1, -1) + else: + assert box.ndim == 2 and box.shape[1] == 6 + + # Extract 3D box parameters + x, y, l, w, h, yaw = box.T + + l = l / 1.8 # 1.8 is the approximate ratio of the length of the car box to the wheel base + + # Create four corner points for the box in global coordinates + corners = np.array([ + [x + l / 2 * np.cos(yaw) - w / 2 * np.sin(yaw), y + l / 2 * np.sin(yaw) + w / 2 * np.cos(yaw)], + [x + l / 2 * np.cos(yaw) + w / 2 * np.sin(yaw), y + l / 2 * np.sin(yaw) - w / 2 * np.cos(yaw)], + [x - l / 2 * np.cos(yaw) + w / 2 * np.sin(yaw), y - l / 2 * np.sin(yaw) - w / 2 * np.cos(yaw)], + [x - l / 2 * np.cos(yaw) - w / 2 * np.sin(yaw), y - l / 2 * np.sin(yaw) + w / 2 * np.cos(yaw)], + ]) + + corners = np.transpose(corners, (2, 0, 1)) + num_boxes = corners.shape[0] + corners_flat = corners.reshape(-1, 2) + + heights = get_raster_values_at_coords(corners_flat, sim2, height_map) + heights = heights.reshape(num_boxes, 4) + + # Fit a plane to the four corner points using least squares + # Solve for plane coefficients (a, b, c) where z = ax + by + c + A = np.stack([corners[..., 0], + corners[..., 1], + np.ones((num_boxes, 4))], + axis=2) + b = heights + plane_coeffs = np.array([np.linalg.lstsq(A[i], b[i], rcond=None)[0] for i in range(num_boxes)]) + + # Calculate pitch and roll from plane normal vector + # Normal vector is [-a, -b, 1] for plane ax + by - z + c = 0 + normals = np.column_stack([-plane_coeffs[:, 0], -plane_coeffs[:, 1], np.ones(num_boxes)]) + normals = normals / np.linalg.norm(normals, axis=1)[:, np.newaxis] + + # Pitch is angle between normal projection on xz-plane and z-axis + # Roll is angle between normal projection on yz-plane and z-axis + pitch = np.arctan2(normals[:, 0], normals[:, 2]) + roll = np.arctan2(normals[:, 1], normals[:, 2]) + eular_angles = np.stack([yaw, pitch, roll], axis=1) + z_coords = np.mean(heights, axis=1) + h / 2 + + return eular_angles.squeeze(), z_coords.squeeze() + +def get_9dof_state(height_map: np.ndarray, sim2: Sim2, agent_state: np.ndarray): + eular_angles, z_coords = calculate_box_eular_angle_and_z(height_map, sim2, agent_state) + x, y, l, w, h, _ = agent_state.T + yaw, pitch, roll = eular_angles.T + bbox_9dof = np.array( + [x, y, z_coords, l, w, h, yaw, pitch, roll], + ) + return bbox_9dof + +def calculate_agent2bbox(bbox9dof: np.ndarray, agent2global: np.ndarray): + """ + """ + quat = get_quat_from_yaw_pitch_roll(bbox9dof[6:9]) + bbox9dof2global_rotation = quat.rotation_matrix + bbox9dof2global_translation = bbox9dof[:3] + + global2bbox = np.eye(4) + global2bbox[:3, :3] = bbox9dof2global_rotation.T + global2bbox[:3, 3] = -bbox9dof2global_rotation.T @ bbox9dof2global_translation + + agent2bbox = global2bbox @ agent2global + return agent2bbox + +def get_quat_from_yaw_pitch_roll(eular_angles: np.ndarray) -> Quaternion: + yaw, pitch, roll = eular_angles + quat = Quaternion(axis=[0, 0, 1], angle=yaw) * \ + Quaternion(axis=[0, 1, 0], angle=pitch) * \ + Quaternion(axis=[1, 0, 0], angle=roll) + return quat + +def get_bbox2global(height_map: np.ndarray, sim2: Sim2, agent_state: np.ndarray): + bbox9dof = get_9dof_state(height_map, sim2, agent_state) + eular_angles = bbox9dof[6:9] + quat = get_quat_from_yaw_pitch_roll(eular_angles) + trans = bbox9dof[:3] + box2global = np.eye(4) + box2global[:3, :3] = quat.rotation_matrix + box2global[:3, 3] = trans + return box2global diff --git a/src/render/src/utils/portable_utils.py b/src/render/src/utils/portable_utils.py new file mode 100644 index 00000000..70058467 --- /dev/null +++ b/src/render/src/utils/portable_utils.py @@ -0,0 +1,65 @@ +""" +This script is heavily based on the EasyDict class from `easydict` package. +""" +import logging + +logger = logging.getLogger(__name__) + +class AttrDict(dict): + def __init__(self, d=None, **kwargs): + if d is None: + d = {} + if kwargs: + d.update(**kwargs) + + # first check if value is a nested dict + # This change is tailored for torch models' `state_dict`. + updated_dict = {} + for k, v in d.items(): + if "." in k: + k1, k2 = k.split(".", 1) + if k1 not in updated_dict: + updated_dict[k1] = {} + updated_dict[k1][k2] = v + elif k in updated_dict: + assert isinstance(v, dict), f"Conflicting value for key `{k}` found. Value should be a dict." + for subkey in v: + if subkey in updated_dict[k]: + assert updated_dict[k][subkey] == v[subkey], f"Conflicting value for key `{k}.{subkey}` found." + logger.warning(f"Duplicate key `{k}.{subkey} found.") + updated_dict[k].update(v) + else: + updated_dict[k] = v + + for k, v in updated_dict.items(): + setattr(self, k, v) + # Class attributes + for k in self.__class__.__dict__.keys(): + if not (k.startswith("__") and k.endswith("__")) and not k in ("update", "pop"): + setattr(self, k, getattr(self, k)) + + def __setattr__(self, name, value): + if isinstance(value, (list, tuple)): + value = [self.__class__(x) if isinstance(x, dict) else x for x in value] + elif isinstance(value, dict) and not isinstance(value, self.__class__): + value = self.__class__(value) + super(AttrDict, self).__setattr__(name, value) + super(AttrDict, self).__setitem__(name, value) + + __setitem__ = __setattr__ + + def update(self, e=None, **f): + d = e or dict() + d.update(f) + for k in d: + setattr(self, k, d[k]) + + def pop(self, k, d=None): + if hasattr(self, k): + delattr(self, k) + return super(AttrDict, self).pop(k, d) + + +def convert_to_attribute_dict(obj: dict) -> AttrDict: + attributes = AttrDict(obj) + return attributes \ No newline at end of file diff --git a/src/runtime/alpasim_runtime/camera_catalog.py b/src/runtime/alpasim_runtime/camera_catalog.py index a11effeb..def094bc 100644 --- a/src/runtime/alpasim_runtime/camera_catalog.py +++ b/src/runtime/alpasim_runtime/camera_catalog.py @@ -406,6 +406,10 @@ def ensure_camera_defined(self, scene_id: str, logical_id: str) -> None: raise KeyError( f"Camera '{logical_id}' is not defined for scene '{scene_id}'" ) + + def get_local_override_cameras(self) -> list[CameraDefinitionConfig]: + """Return list of locally configured camera overrides.""" + return list(self._local_overrides.values()) __all__ = ["CameraCatalog", "CameraDefinition"] diff --git a/src/runtime/alpasim_runtime/config.py b/src/runtime/alpasim_runtime/config.py index 2348135e..5f69497c 100644 --- a/src/runtime/alpasim_runtime/config.py +++ b/src/runtime/alpasim_runtime/config.py @@ -62,7 +62,7 @@ class NetworkSimulatorConfig: class RuntimeCameraConfig: """Configuration for a camera in the runtime. See `RuntimeCamera` for more details.""" - logical_id: str = "camera_front_wide_120fov" + logical_id: str = "" height: int = 160 width: int = 256 frame_interval_us: int = 33_000 # about 30fps diff --git a/src/runtime/alpasim_runtime/dispatcher.py b/src/runtime/alpasim_runtime/dispatcher.py index 451f3612..56d2b8d9 100644 --- a/src/runtime/alpasim_runtime/dispatcher.py +++ b/src/runtime/alpasim_runtime/dispatcher.py @@ -31,6 +31,8 @@ from alpasim_runtime.services.traffic_service import TrafficService from alpasim_runtime.worker.ipc import JobResult, RolloutJob, ServiceAllocations from alpasim_utils.artifact import Artifact +from alpasim_utils.data_source_loader import load_data_sources +from alpasim_utils.scene_data_source import SceneDataSource logger = logging.getLogger(__name__) @@ -51,7 +53,7 @@ class Dispatcher: camera_catalog: CameraCatalog user_config: UserSimulatorConfig - artifacts: dict[str, Artifact] + artifacts: dict[str, SceneDataSource] version_ids: RolloutMetadata.VersionIds asl_dir: str @@ -72,15 +74,27 @@ async def find_scenario_incompatibilities( async def create( user_config: UserSimulatorConfig, allocations: ServiceAllocations, - usdz_glob: str, - asl_dir: str, + usdz_glob: str | None = None, + asl_dir: str = "", + trajdata_config_path: str | None = None, ) -> Dispatcher: - """Initialize dispatcher: discover artifacts, build pools from allocations.""" + """ + Initialize dispatcher: discover artifacts, build pools from allocations. + + Args: + user_config: User simulator configuration + allocations: Service allocations + usdz_glob: Glob pattern for USDZ files (mutually exclusive with trajdata_config_path) + asl_dir: Directory for ASL output files + trajdata_config_path: Path to JSON/YAML file containing trajdata configuration + """ camera_catalog = CameraCatalog(user_config.extra_cameras) # NOTE: In multi-worker mode, each worker re-discovers artifacts independently. - artifacts = Artifact.discover_from_glob( - usdz_glob, smooth_trajectories=user_config.smooth_trajectories + artifacts = load_data_sources( + usdz_glob=usdz_glob, + trajdata_config_path=trajdata_config_path, + smooth_trajectories=user_config.smooth_trajectories, ) endpoints = user_config.endpoints diff --git a/src/runtime/alpasim_runtime/loop.py b/src/runtime/alpasim_runtime/loop.py index 0ceb8d40..a7aa7a25 100644 --- a/src/runtime/alpasim_runtime/loop.py +++ b/src/runtime/alpasim_runtime/loop.py @@ -48,6 +48,7 @@ from alpasim_runtime.telemetry.telemetry_context import try_get_context from alpasim_runtime.types import Clock, RuntimeCamera from alpasim_utils.artifact import Artifact +from alpasim_utils.scene_data_source import SceneDataSource from alpasim_utils.logs import LogWriter from alpasim_utils.qvec import QVec from alpasim_utils.scenario import AABB, TrafficObjects @@ -140,7 +141,7 @@ def create( scenario: ScenarioConfig, version_ids: RolloutMetadata.VersionIds, random_seed: int, - available_artifacts: dict[str, Artifact], + available_artifacts: dict[str, SceneDataSource], asl_dir: str, ) -> UnboundRollout: diff --git a/src/runtime/alpasim_runtime/services/mtgs_sensorsim_server.py b/src/runtime/alpasim_runtime/services/mtgs_sensorsim_server.py new file mode 100644 index 00000000..c92fcf13 --- /dev/null +++ b/src/runtime/alpasim_runtime/services/mtgs_sensorsim_server.py @@ -0,0 +1,267 @@ +# SPDX-License-Identifier: Apache-2.0 +# Copyright (c) 2025 NVIDIA Corporation + +""" +Server script for MTGS Sensorsim Service. + +This script starts a gRPC server that exposes the MTGS renderer +as a SensorsimService, allowing it to replace the default sensorsim in alpasim. +""" + +import argparse +import json +import logging +from concurrent import futures +from pathlib import Path + +import grpc + +from alpasim_grpc.v0.sensorsim_pb2_grpc import add_SensorsimServiceServicer_to_server +from alpasim_runtime.services.mtgs_sensorsim_service import ( + MTGSSensorsimService, +) +from alpasim_utils.data_source_loader import load_data_sources + +logger = logging.getLogger(__name__) + +# Mapping from trajdata dataset names to MTGS asset folder subdirectories +# Format: "nuplan_" -> "data_nav" +TRAJDATA_TO_ASSET_FOLDER_MAPPING = { + "nuplan_test": "navtest", + "nuplan_train": "navtrain", + # Add more mappings as needed +} + + +def parse_args(arg_list: list[str] | None = None) -> tuple[argparse.Namespace, list[str]]: + """Parse command line arguments.""" + parser = argparse.ArgumentParser( + description="MTGS Sensorsim Service Server", + formatter_class=argparse.ArgumentDefaultsHelpFormatter, + ) + artifact_group = parser.add_mutually_exclusive_group(required=True) + artifact_group.add_argument( + "--artifact-glob", + type=str, + help="Glob expression to find USDZ artifacts. Must end in .usdz", + ) + artifact_group.add_argument( + "--trajdata-config", + type=str, + help="Path to trajdata config YAML/JSON file", + ) + parser.add_argument( + "--asset-folder-path", + type=str, + help="Path to MTGS asset folder containing scene assets", + required=True, + ) + parser.add_argument( + "--scene-id-to-asset-id-mapping", + type=str, + help="Optional JSON file mapping scene_id to asset_id", + default=None, + ) + parser.add_argument("--host", type=str, default="localhost", help="Host to bind to") + parser.add_argument("--port", type=int, default=8080, help="Port to bind to") + parser.add_argument( + "--cache-size", + type=int, + default=2, + help="Number of renderer instances to keep in LRU cache", + ) + parser.add_argument( + "--device", + type=str, + default="cuda", + choices=["cuda", "cpu"], + help="Device to use for rendering", + ) + parser.add_argument( + "--log-level", + type=str, + default="INFO", + choices=["DEBUG", "INFO", "WARNING", "ERROR"], + help="Logging level", + ) + args, overrides = parser.parse_known_args(arg_list) + return args, overrides + + +def load_scene_id_mapping(mapping_path: str | None) -> dict[str, str] | None: + """Load scene_id to asset_id mapping from JSON file.""" + if mapping_path is None: + return None + + mapping_file = Path(mapping_path) + if not mapping_file.exists(): + logger.warning(f"Mapping file not found: {mapping_path}") + return None + + try: + with open(mapping_file, "r") as f: + mapping = json.load(f) + logger.info(f"Loaded {len(mapping)} scene_id mappings from {mapping_path}") + return mapping + except Exception as e: + logger.error(f"Failed to load mapping file: {e}") + return None + + +def resolve_asset_folder_path( + base_asset_folder_path: str, + trajdata_config_path: str | None = None, +) -> str: + """ + Resolve the full asset folder path based on trajdata config. + + If trajdata_config_path is provided, reads the desired_data from the config + and automatically appends the corresponding subdirectory to the base path. + + Args: + base_asset_folder_path: Base path to MTGS asset folder + trajdata_config_path: Optional path to trajdata config YAML/JSON file + + Returns: + Resolved asset folder path (with subdirectory appended if applicable) + + Examples: + If base_asset_folder_path="/path/to/assets" and trajdata config has + desired_data=["nuplan_test"], returns "/path/to/assets/data_navtest" + """ + base_path = Path(base_asset_folder_path) + + # If no trajdata config, return base path as-is + if trajdata_config_path is None: + return str(base_path) + + # Load trajdata config to extract desired_data + config_path = Path(trajdata_config_path) + if not config_path.exists(): + logger.warning( + f"Trajdata config file not found: {config_path}. " + f"Using base asset folder path: {base_path}" + ) + return str(base_path) + + try: + with open(config_path, "r") as f: + if config_path.suffix.lower() in [".yaml", ".yml"]: + import yaml + config = yaml.safe_load(f) + else: + # Assume JSON + config = json.load(f) + + # Extract desired_data from config + desired_data = config.get("desired_data", []) + if not desired_data: + logger.warning( + f"No 'desired_data' found in trajdata config. " + f"Using base asset folder path: {base_path}" + ) + return str(base_path) + + # Use the first dataset name in desired_data + # (typically there's only one, but if multiple, use the first) + dataset_name = desired_data[0] if isinstance(desired_data, list) else desired_data + + # Look up the corresponding asset folder subdirectory + asset_subdir = TRAJDATA_TO_ASSET_FOLDER_MAPPING.get(dataset_name) + + if asset_subdir is None: + logger.warning( + f"No mapping found for dataset '{dataset_name}'. " + f"Available mappings: {list(TRAJDATA_TO_ASSET_FOLDER_MAPPING.keys())}. " + f"Using base asset folder path: {base_path}" + ) + return str(base_path) + + # Construct full path: base_path / asset_subdir + full_path = base_path / asset_subdir / 'assets' + + # Verify the path exists + if not full_path.exists(): + logger.warning( + f"Asset folder subdirectory does not exist: {full_path}. " + f"Using base asset folder path: {base_path}" + ) + return str(base_path) + + logger.info( + f"Auto-resolved asset folder path: {base_path} -> {full_path} " + f"(based on dataset '{dataset_name}' -> '{asset_subdir}')" + ) + return str(full_path) + + except Exception as e: + logger.error( + f"Failed to resolve asset folder path from trajdata config: {e}. " + f"Using base asset folder path: {base_path}" + ) + return str(base_path) + + +def main(arg_list: list[str] | None = None) -> None: + """Main entry point for the server.""" + args, _ = parse_args(arg_list) + + logging.basicConfig( + level=getattr(logging, args.log_level.upper(), logging.INFO), + format="%(asctime)s.%(msecs)03d %(levelname)s:\t%(message)s", + datefmt="%H:%M:%S", + ) + + logger.info("Starting MTGS Sensorsim Service") + + # Resolve asset folder path based on trajdata config if provided + # This automatically appends the correct subdirectory (e.g., data_navtest) + # based on the desired_data in trajdata config + resolved_asset_folder_path = resolve_asset_folder_path( + base_asset_folder_path=args.asset_folder_path, + trajdata_config_path=args.trajdata_config if not args.artifact_glob else None, + ) + + # Load artifacts from either USDZ glob or trajdata config + if args.artifact_glob: + logger.info(f"Loading artifacts from USDZ glob: {args.artifact_glob}") + artifacts = load_data_sources(usdz_glob=args.artifact_glob) + else: + logger.info(f"Loading artifacts from trajdata config: {args.trajdata_config}") + artifacts = load_data_sources(trajdata_config_path=args.trajdata_config) + + logger.info(f"Asset folder path: {resolved_asset_folder_path}") + logger.info(f"Device: {args.device}") + logger.info(f"Loaded {len(artifacts)} scenes") + + # Load scene_id to asset_id mapping if provided + scene_id_mapping = load_scene_id_mapping(args.scene_id_to_asset_id_mapping) + + # Create gRPC server + server = grpc.server(futures.ThreadPoolExecutor(max_workers=4)) + address = f"{args.host}:{args.port}" + server.add_insecure_port(address) + + # Create and register service + service = MTGSSensorsimService( + server=server, + artifacts=artifacts, + asset_folder_path=resolved_asset_folder_path, + scene_id_to_asset_id_mapping=scene_id_mapping, + cache_size=args.cache_size, + device=args.device, + ) + add_SensorsimServiceServicer_to_server(service, server) + + logger.info(f"Serving MTGS Sensorsim Service on {address}") + server.start() + + try: + server.wait_for_termination() + except KeyboardInterrupt: + logger.info("Received interrupt signal, shutting down...") + server.stop(0) + + +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/src/runtime/alpasim_runtime/services/mtgs_sensorsim_service.py b/src/runtime/alpasim_runtime/services/mtgs_sensorsim_service.py new file mode 100644 index 00000000..3784e1c6 --- /dev/null +++ b/src/runtime/alpasim_runtime/services/mtgs_sensorsim_service.py @@ -0,0 +1,788 @@ +# SPDX-License-Identifier: Apache-2.0 +# Copyright (c) 2025 NVIDIA Corporation + +""" +MTGS Sensorsim Service implementation. + +This service wraps the MTGS renderer and exposes it via gRPC +as a SensorsimService, allowing it to replace the default sensorsim in alpasim. +""" + +from __future__ import annotations + +import functools +import io +import logging +import time +from pathlib import Path +from typing import Dict, Optional + +import cv2 +import grpc +import numpy as np +import torch + +from alpasim_grpc.v0.common_pb2 import AvailableScenesReturn, Empty, VersionId +from alpasim_grpc.v0.sensorsim_pb2 import ( + AggregatedRenderRequest, + AggregatedRenderReturn, + AvailableCamerasRequest, + AvailableCamerasReturn, + AvailableEgoMasksReturn, + AvailableTrajectoriesRequest, + AvailableTrajectoriesReturn, + RGBRenderRequest, + RGBRenderReturn, +) +from alpasim_grpc.v0.sensorsim_pb2_grpc import SensorsimServiceServicer +from alpasim_utils.artifact import Artifact +from alpasim_utils.mtgs_artifact_adapter import ( + get_available_cameras_from_data_source, + rgb_render_request_to_render_state, +) +from alpasim_utils.scene_data_source import SceneDataSource + +logger = logging.getLogger(__name__) + +# Import MTGS renderer from local render module +try: + from src.render.src.mtgs import MTGS + from src.render.base_renderer import RenderState + MTGS_AVAILABLE = True +except ImportError as e: + logger.warning(f"MTGS renderer not available: {e}") + MTGS_AVAILABLE = False + MTGS = None + RenderState = None + + +VERSION_MESSAGE = VersionId( + version_id="mtgs-sensorsim-1.0.0", + git_hash="unknown", +) + + +class MTGSSensorsimService(SensorsimServiceServicer): + """ + gRPC service that wraps MTGS renderer. + + This service implements the SensorsimServiceServicer interface, allowing + MTGS to be used as a drop-in replacement for the default sensorsim. + """ + + def __init__( + self, + server: grpc.Server, + artifacts: Dict[str, SceneDataSource], + asset_folder_path: str, + scene_id_to_asset_id_mapping: Optional[Dict[str, str]] = None, + cache_size: int = 2, + device: str = "cuda" if torch.cuda.is_available() else "cpu", + ) -> None: + """ + Initialize the MTGS sensorsim service. + + Args: + server: gRPC server instance + artifacts: Dictionary mapping scene_id to SceneDataSource (from load_data_sources) + asset_folder_path: Path to MTGS asset folder + scene_id_to_asset_id_mapping: Optional mapping from scene_id to asset_id + cache_size: Number of renderer instances to cache + device: Device to use for rendering (cuda or cpu) + """ + if not MTGS_AVAILABLE: + raise ImportError("MTGS renderer is required for MTGSSensorsimService") + + self.server = server + self.artifacts: Dict[str, SceneDataSource] = artifacts + self.asset_folder_path = Path(asset_folder_path) + self.scene_id_to_asset_id_mapping = scene_id_to_asset_id_mapping or {} + self.device = device + + logger.info(f"Available scenes: {list(self.artifacts.keys())}") + logger.info(f"Asset folder path: {self.asset_folder_path}") + + # Cache renderer instances per scene + # Note: We can't use lru_cache directly because it needs to access self.artifacts + # Instead, we'll manually cache renderers + self._renderer_cache: Dict[str, MTGS] = {} + + def get_renderer(scene_id: str) -> MTGS: + if scene_id in self._renderer_cache: + return self._renderer_cache[scene_id] + + if scene_id not in self.artifacts: + raise KeyError(f"Scene {scene_id=} not available.") + + artifact = self.artifacts[scene_id] + logger.info(f"Cache miss, loading renderer for {scene_id=}") + + # Get asset_id from mapping or use scene_id + asset_id = self.scene_id_to_asset_id_mapping.get(scene_id, scene_id) + + # Create renderer with asset_folder_path from service config + renderer = MTGS( + device=self.device, + asset_folder_path=self.asset_folder_path + ) + + # Clean asset_id (remove suffix like "-001") + asset_id_clean = asset_id + if asset_id_clean[-4:].startswith('-'): # Remove suffix like "-001" + asset_id_clean = asset_id_clean[:-4] + + # Reset renderer with asset_id + renderer.reset(current_scene_id=scene_id, asset_id=asset_id_clean) + + # Calculate ego2globals - priority: video_scene_dict > rig trajectory + ego2globals = None + + # First, try to get from video_scene_dict.pkl (preferred source) + try: + if hasattr(renderer.asset_manager, 'video_scene_dict') and renderer.asset_manager.video_scene_dict: + video_dict_raw = renderer.asset_manager.video_scene_dict + + # Handle nested structure: video_scene_dict may be {scene_id: {frame_infos, ego2global, ...}} + # or directly {frame_infos, ego2global, ...} + video_dict = video_dict_raw + if isinstance(video_dict_raw, dict) and 'ego2global' not in video_dict_raw and 'frame_infos' not in video_dict_raw: + # Nested structure - get the first (and usually only) scene data + first_key = next(iter(video_dict_raw.keys()), None) + if first_key and isinstance(video_dict_raw[first_key], dict): + video_dict = video_dict_raw[first_key] + logger.info(f"Accessing nested video_scene_dict with key: {first_key}") + + # Check for frame_infos FIRST (more common case with 301 frames) + if 'frame_infos' in video_dict and len(video_dict['frame_infos']) > 0: + # Extract ego2global from frame_infos (each frame has its own ego2global) + frame_infos = video_dict['frame_infos'] + logger.info(f"Found {len(frame_infos)} frames in frame_infos, extracting ego2globals...") + ego2globals_list = [] + for fi in frame_infos: + if 'ego2global' in fi: + ego2globals_list.append(np.array(fi['ego2global'])) + elif 'ego2global_translation' in fi and 'ego2global_rotation' in fi: + transform = np.eye(4) + transform[:3, 3] = np.array(fi['ego2global_translation']) + rot = np.array(fi['ego2global_rotation']) + if rot.shape == (3, 3): + transform[:3, :3] = rot + elif rot.shape == (4,): # quaternion + from pyquaternion import Quaternion + q = Quaternion(rot[0], rot[1], rot[2], rot[3]) + transform[:3, :3] = q.rotation_matrix + ego2globals_list.append(transform) + if ego2globals_list: + ego2globals = np.stack(ego2globals_list) + logger.info(f"✓ Extracted ego2globals from frame_infos: shape {ego2globals.shape}, first translation: {ego2globals[0, :3, 3]}") + elif 'ego2global' in video_dict: + ego2globals = np.array(video_dict['ego2global']) + if ego2globals.ndim == 2: + # Single matrix, add batch dimension + ego2globals = ego2globals[np.newaxis, ...] + logger.info(f"Loaded ego2globals from video_scene_dict: shape {ego2globals.shape}") + elif 'ego2global_translation' in video_dict and 'ego2global_rotation' in video_dict: + # Reconstruct from translation and rotation + translations = np.array(video_dict['ego2global_translation']) + rotations = np.array(video_dict['ego2global_rotation']) + if translations.ndim == 1: + translations = translations[np.newaxis, ...] + if rotations.ndim == 2: + rotations = rotations[np.newaxis, ...] + + ego2globals_list = [] + for i in range(len(translations)): + transform = np.eye(4) + transform[:3, :3] = rotations[i] if rotations.shape[-1] == 3 else rotations[i].reshape(3, 3) + transform[:3, 3] = translations[i] + ego2globals_list.append(transform) + ego2globals = np.stack(ego2globals_list) + logger.info(f"Reconstructed ego2globals from video_scene_dict: shape {ego2globals.shape}") + except Exception as e: + logger.warning(f"Could not load ego2globals from video_scene_dict: {e}") + + # Fallback: compute from rig trajectory if video_scene_dict not available + if ego2globals is None: + try: + rig = artifact.rig + if rig.trajectory.poses is not None and len(rig.trajectory.poses) > 0: + # Convert rig trajectory poses to ego2global transformation matrices + poses = rig.trajectory.poses + ego2globals_list = [] + for pose in poses: + # Create 4x4 transformation matrix from pose + # Handle different pose formats (gRPC objects vs numpy arrays) + if hasattr(pose.vec3, '__getitem__'): # numpy array or similar + trans = np.array([pose.vec3[0], pose.vec3[1], pose.vec3[2]]) + else: # gRPC object with .x, .y, .z attributes + trans = np.array([pose.vec3.x, pose.vec3.y, pose.vec3.z]) + + if hasattr(pose.quat, 'w'): # gRPC object with .w, .x, .y, .z attributes + quat = np.array([pose.quat.w, pose.quat.x, pose.quat.y, pose.quat.z]) + elif hasattr(pose.quat, '__getitem__'): # numpy array or similar + quat = np.array(pose.quat) + else: + raise ValueError(f"Unsupported quaternion format: {type(pose.quat)}") + + # Convert quaternion to rotation matrix using proper function + from src.render.src.utils.gaussian_utils import quat_to_rotmat + quat_tensor = torch.tensor(quat, dtype=torch.float64).unsqueeze(0) # [1, 4] + rot_mat = quat_to_rotmat(quat_tensor).squeeze(0).numpy() # [3, 3] + + # Create 4x4 transformation matrix + transform = np.eye(4) + transform[:3, :3] = rot_mat + transform[:3, 3] = trans + ego2globals_list.append(transform) + + ego2globals = np.stack(ego2globals_list) + logger.info(f"Computed ego2globals from rig trajectory: shape {ego2globals.shape}") + except Exception as e: + logger.warning(f"Could not compute ego2globals from rig trajectory: {e}") + + # Set world_to_nre transformation from Rig + # This enables Simulator Local → Nuplan Global coordinate conversion in render() + if hasattr(artifact, 'rig') and artifact.rig is not None: + if hasattr(artifact.rig, 'world_to_nre') and artifact.rig.world_to_nre is not None: + renderer.set_world_to_nre(artifact.rig.world_to_nre) + logger.info(f"Set world_to_nre from rig: {artifact.rig.world_to_nre[:3, 3]}") + else: + logger.warning("artifact.rig exists but world_to_nre is None") + else: + logger.warning("artifact.rig not available, world_to_nre not set") + + # Calibrate agent states (will use ego2globals if provided) + renderer.mtgs_agent2states = renderer.calibrate_agent_state(ego2globals=ego2globals) + + # NOTE: No coordinate offset conversion needed! + # - Runtime sends ego_pose already in global coordinates + # - MTGS.render() will subtract recon2global_translation internally + # - get_agent_pose() does nearest-neighbor search in reconstruction coordinate system + # + # Coordinate flow: + # 1. Runtime: ego_pose in global frame [x_global, y_global, ...] + # 2. Service: passes through unchanged + # 3. MTGS.render(): subtracts recon2global_translation → reconstruction frame + # 4. get_agent_pose(): matches in reconstruction frame against mtgs_agent2states + # 5. mtgs_agent2states contains: video_scene_dict.ego2global (global) - recon2global + # + # Therefore: NO offset conversion is needed in the service layer + renderer.local_to_global_offset = None # Not used + logger.info("Coordinate system: Runtime sends global, MTGS handles conversion internally") + + renderer._scene_id = scene_id + renderer._asset_id = asset_id + renderer._initialized = True + + # Cache the renderer (simple LRU: keep only cache_size most recent) + if len(self._renderer_cache) >= cache_size: + # Remove oldest entry (first key) + oldest_key = next(iter(self._renderer_cache)) + del self._renderer_cache[oldest_key] + + self._renderer_cache[scene_id] = renderer + return renderer + + self.get_renderer = get_renderer + + def get_version(self, request: Empty, context: grpc.ServicerContext) -> VersionId: + """Return version information.""" + return VERSION_MESSAGE + + def get_available_scenes( + self, request: Empty, context: grpc.ServicerContext + ) -> AvailableScenesReturn: + """Return list of available scene IDs.""" + return AvailableScenesReturn(scene_ids=list(self.artifacts.keys())) + + def get_available_cameras( + self, + request: AvailableCamerasRequest, + context: grpc.ServicerContext, + ) -> AvailableCamerasReturn: + """Return available cameras for a scene.""" + scene_id = request.scene_id + renderer = self.get_renderer(scene_id) + if scene_id not in self.artifacts: + context.set_code(grpc.StatusCode.NOT_FOUND) + context.set_details(f"Scene {scene_id} not found") + return AvailableCamerasReturn() + + cameras = get_available_cameras_from_data_source(asset_manager=renderer.asset_manager) + + return AvailableCamerasReturn(available_cameras=cameras) + + def get_available_trajectories( + self, + request: AvailableTrajectoriesRequest, + context: grpc.ServicerContext, + ) -> AvailableTrajectoriesReturn: + """Return available trajectories for a scene.""" + scene_id = request.scene_id + if scene_id not in self.artifacts: + context.set_code(grpc.StatusCode.NOT_FOUND) + context.set_details(f"Scene {scene_id} not found") + return AvailableTrajectoriesReturn() + + artifact = self.artifacts[scene_id] + rig = artifact.rig + + return AvailableTrajectoriesReturn( + available_trajectories=[ + AvailableTrajectoriesReturn.AvailableTrajectory( + trajectory=rig.trajectory.to_grpc() + ) + ] + ) + + def get_available_ego_masks( + self, request: Empty, context: grpc.ServicerContext + ) -> AvailableEgoMasksReturn: + """Return available ego masks (empty for now).""" + # MTGS doesn't support ego masks yet + return AvailableEgoMasksReturn() + + def render_rgb( + self, request: RGBRenderRequest, context: grpc.ServicerContext + ) -> RGBRenderReturn: + """Render an RGB image using MTGS.""" + try: + scene_id = request.scene_id + camera_name = request.camera_intrinsics.logical_id + frame_start_us = request.frame_start_us + + if scene_id not in self.artifacts: + context.set_code(grpc.StatusCode.NOT_FOUND) + context.set_details(f"Scene {scene_id} not found") + return RGBRenderReturn() + + artifact = self.artifacts[scene_id] + + # Get or create renderer for this scene + renderer = self.get_renderer(scene_id) + + # Convert RGBRenderRequest to RenderState + # Pass asset_manager to allow access to video_scene_dict for ego2global info + render_state_dict = rgb_render_request_to_render_state( + request, + asset_manager=renderer.asset_manager + ) + + # NOTE: No coordinate conversion needed - Runtime sends global coordinates + # MTGS.render() will handle the conversion internally by subtracting recon2global_translation + + # Create RenderState object + # Note: RenderState is a dict subclass, so we can use dict assignment + render_state = RenderState() + render_state[RenderState.TIMESTAMP] = render_state_dict["timestamp"] + render_state[RenderState.AGENT_STATE] = render_state_dict["agent_state"] + render_state[RenderState.CAMERAS] = render_state_dict["cameras"] + render_state[RenderState.LIDAR] = render_state_dict.get("lidar", {}) + + # Set recon2global_translation if not set (needed for coordinate transformation) + if not hasattr(renderer, 'recon2global_translation'): + # Try to get from asset manager + if hasattr(renderer.asset_manager, 'background_asset_dict') and renderer.asset_manager.background_asset_dict: + bg_asset = renderer.asset_manager.background_asset_dict + if 'background' in bg_asset and 'config' in bg_asset['background']: + recon2global = bg_asset['background']['config'].get('recon2world_translation', [0.0, 0.0, 0.0]) + renderer.recon2global_translation = torch.tensor(recon2global[:2], device=self.device) + else: + renderer.recon2global_translation = torch.zeros(2, device=self.device) + else: + renderer.recon2global_translation = torch.zeros(2, device=self.device) + + # Ensure renderer is initialized for this scene + # The renderer should already be initialized in get_renderer, but check anyway + if not hasattr(renderer, '_initialized') or not renderer._initialized or renderer._scene_id != scene_id: + # Re-initialize if needed + asset_id = self.scene_id_to_asset_id_mapping.get(scene_id, scene_id) + asset_id_clean = asset_id + if asset_id_clean[-4:].startswith('-'): + asset_id_clean = asset_id_clean[:-4] + + reset_asset = renderer.asset_manager.reset(asset_id_clean) + if reset_asset: + renderer._prepare_metas() + renderer._init_gaussian_models() + renderer.set_asset(renderer.asset_manager.background_asset_dict) + + # Calibrate agent states properly using ego2globals + ego2globals = None + try: + # Try to get from video_scene_dict first + if hasattr(renderer.asset_manager, 'video_scene_dict') and renderer.asset_manager.video_scene_dict: + video_dict = renderer.asset_manager.video_scene_dict + # Handle nested structure + if isinstance(video_dict, dict) and 'ego2global' not in video_dict and 'frame_infos' not in video_dict: + first_key = next(iter(video_dict.keys()), None) + if first_key and isinstance(video_dict[first_key], dict): + video_dict = video_dict[first_key] + + # Check for frame_infos first (more common, 301 frames) + if 'frame_infos' in video_dict and len(video_dict['frame_infos']) > 0: + frame_infos = video_dict['frame_infos'] + ego2globals_list = [] + for fi in frame_infos: + if 'ego2global' in fi: + ego2globals_list.append(np.array(fi['ego2global'])) + if ego2globals_list: + ego2globals = np.stack(ego2globals_list) + elif 'ego2global' in video_dict: + ego2globals = np.array(video_dict['ego2global']) + if ego2globals.ndim == 2: + ego2globals = ego2globals[np.newaxis, ...] + + # Fallback to rig trajectory + if ego2globals is None: + rig = artifact.rig + if rig.trajectory.poses is not None and len(rig.trajectory.poses) > 0: + poses = rig.trajectory.poses + ego2globals_list = [] + for pose in poses: + if hasattr(pose.vec3, 'x'): + trans = np.array([pose.vec3.x, pose.vec3.y, pose.vec3.z]) + else: + trans = np.array([pose.vec3[0], pose.vec3[1], pose.vec3[2]]) + + if hasattr(pose.quat, 'w'): + quat = np.array([pose.quat.w, pose.quat.x, pose.quat.y, pose.quat.z]) + else: + quat = np.array(pose.quat) + + from src.render.src.utils.gaussian_utils import quat_to_rotmat + quat_tensor = torch.tensor(quat, dtype=torch.float64).unsqueeze(0) + rot_mat = quat_to_rotmat(quat_tensor).squeeze(0).numpy() + + transform = np.eye(4) + transform[:3, :3] = rot_mat + transform[:3, 3] = trans + ego2globals_list.append(transform) + + ego2globals = np.stack(ego2globals_list) + except Exception as e: + logger.warning(f"Could not compute ego2globals: {e}") + + # Calibrate agent states with ego2globals + renderer.mtgs_agent2states = renderer.calibrate_agent_state(ego2globals=ego2globals) + + renderer.sensor_caches = None + + renderer._scene_id = scene_id + renderer._asset_id = asset_id + renderer._initialized = True + + # Render + result = renderer.render(render_state) + + # Extract image from result + # result should be a dict with 'cameras' key containing camera images + if "cameras" not in result: + raise ValueError("Renderer did not return cameras in result") + + cameras_dict = result["cameras"] + if not cameras_dict: + raise ValueError("No cameras in render result") + + # Get the first camera image (or the requested camera) + camera_name = request.camera_intrinsics.logical_id + if camera_name in cameras_dict and "image" in cameras_dict[camera_name]: + image = cameras_dict[camera_name]["image"] + else: + # Fallback to first available camera + first_camera = next(iter(cameras_dict.values())) + image = first_camera.get("image") + + if image is None: + raise ValueError("No image found in render result") + + # Convert image to bytes + # image should be a numpy array (BGR format from OpenCV) + if isinstance(image, np.ndarray): + # Encode as JPEG or PNG based on request + if request.image_format == 1: # PNG + success, image_bytes = cv2.imencode(".png", image) + elif request.image_format == 2: # JPEG + success, image_bytes = cv2.imencode( + ".jpg", image, [cv2.IMWRITE_JPEG_QUALITY, int(request.image_quality)] + ) + else: + # Default to JPEG + success, image_bytes = cv2.imencode(".jpg", image) + + if not success: + raise ValueError("Failed to encode image") + + # Save rendered image to disk for debugging/visualization + self._save_rendered_image(image, scene_id, camera_name, request.frame_start_us) + + return RGBRenderReturn(image_bytes=image_bytes.tobytes()) + else: + raise ValueError(f"Unexpected image type: {type(image)}") + + except Exception as e: + logger.exception(f"Error rendering RGB image: {e}") + context.set_code(grpc.StatusCode.INTERNAL) + context.set_details(str(e)) + raise + + def render_aggregated( + self, + request: AggregatedRenderRequest, + context: grpc.ServicerContext, + ) -> AggregatedRenderReturn: + """Render multiple RGB images efficiently by batching.""" + if not request.rgb_requests: + return AggregatedRenderReturn() + + # Check if all requests can be batched (same scene, same timestamp) + first_request = request.rgb_requests[0] + scene_id = first_request.scene_id + frame_start_us = first_request.frame_start_us + + can_batch = all( + req.scene_id == scene_id and req.frame_start_us == frame_start_us + for req in request.rgb_requests + ) + + if not can_batch: + # Fallback: render each request individually + logger.warning( + f"Cannot batch render_aggregated: requests have different scenes or timestamps. " + f"Falling back to sequential rendering." + ) + rgb_returns = [] + for rgb_request in request.rgb_requests: + rgb_return = self.render_rgb(rgb_request, context) + rgb_returns.append(rgb_return) + return AggregatedRenderReturn(rgb_returns=rgb_returns) + + # Optimized path: batch render all cameras in one call + try: + return self._render_aggregated_batch(request, context) + except Exception as e: + logger.exception(f"Batch rendering failed: {e}. Falling back to sequential rendering.") + # Fallback to sequential rendering + rgb_returns = [] + for rgb_request in request.rgb_requests: + try: + rgb_return = self.render_rgb(rgb_request, context) + rgb_returns.append(rgb_return) + except Exception as req_error: + logger.error(f"Failed to render camera {rgb_request.camera_intrinsics.logical_id}: {req_error}") + rgb_returns.append(RGBRenderReturn()) # Empty response for failed camera + return AggregatedRenderReturn(rgb_returns=rgb_returns) + + def _render_aggregated_batch( + self, + request: AggregatedRenderRequest, + context: grpc.ServicerContext, + ) -> AggregatedRenderReturn: + """ + Optimized batch rendering: render once, extract all cameras. + + This method assumes all requests have the same scene_id and frame_start_us. + """ + first_request = request.rgb_requests[0] + scene_id = first_request.scene_id + + if scene_id not in self.artifacts: + context.set_code(grpc.StatusCode.NOT_FOUND) + context.set_details(f"Scene {scene_id} not found") + return AggregatedRenderReturn() + + artifact = self.artifacts[scene_id] + renderer = self.get_renderer(scene_id) + + # Convert first request to RenderState (all requests share same ego state and timestamp) + render_state_dict = rgb_render_request_to_render_state( + first_request, + asset_manager=renderer.asset_manager + ) + render_state = RenderState(**render_state_dict) + + # Single render call for all cameras + logger.info(f"Batch rendering {len(request.rgb_requests)} cameras for scene {scene_id}") + result = renderer.render(render_state) + + if "cameras" not in result: + raise ValueError("Renderer did not return cameras in result") + + cameras_dict = result["cameras"] + if not cameras_dict: + raise ValueError("No cameras in render result") + + # Extract and encode images for all requested cameras + rgb_returns = [] + for rgb_request in request.rgb_requests: + camera_name = rgb_request.camera_intrinsics.logical_id + + # Get image for this camera + if camera_name in cameras_dict and "image" in cameras_dict[camera_name]: + image = cameras_dict[camera_name]["image"] + else: + logger.warning(f"Camera {camera_name} not found in render result, using first available") + first_camera = next(iter(cameras_dict.values())) + image = first_camera.get("image") + + if image is None: + logger.error(f"No image found for camera {camera_name}") + rgb_returns.append(RGBRenderReturn()) + continue + + # Encode image + if not isinstance(image, np.ndarray): + logger.error(f"Unexpected image type for camera {camera_name}: {type(image)}") + rgb_returns.append(RGBRenderReturn()) + continue + + # Encode based on format + if rgb_request.image_format == 1: # PNG + success, image_bytes = cv2.imencode(".png", image) + elif rgb_request.image_format == 2: # JPEG + success, image_bytes = cv2.imencode( + ".jpg", image, [cv2.IMWRITE_JPEG_QUALITY, int(rgb_request.image_quality)] + ) + else: + # Default to JPEG + success, image_bytes = cv2.imencode(".jpg", image) + + if not success: + logger.error(f"Failed to encode image for camera {camera_name}") + rgb_returns.append(RGBRenderReturn()) + continue + + # Save rendered image to disk for debugging/visualization + self._save_rendered_image(image, scene_id, camera_name, rgb_request.frame_start_us) + + rgb_returns.append(RGBRenderReturn(image_bytes=image_bytes.tobytes())) + + logger.info(f"Batch rendering completed: {len(rgb_returns)}/{len(request.rgb_requests)} cameras successful") + + # Save panorama view combining all cameras + self._save_panorama_view(cameras_dict, scene_id, first_request.frame_start_us) + + return AggregatedRenderReturn(rgb_returns=rgb_returns) + + def render_lidar( + self, request, context: grpc.ServicerContext + ): + """Render LiDAR data (not implemented yet).""" + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details("LiDAR rendering not implemented for MTGS") + raise NotImplementedError("LiDAR rendering not implemented") + + def shut_down(self, request: Empty, context: grpc.ServicerContext) -> Empty: + """Shut down the service.""" + logger.info("shut_down") + context.add_callback(self._shut_down) + return Empty() + + def _save_rendered_image( + self, + image: np.ndarray, + scene_id: str, + camera_id: str, + timestamp_us: int + ) -> None: + """Save rendered image to disk for visualization. + + Images are saved to: {workspace}/rendered_images/{scene_id}/{camera_id}_{timestamp}.jpg + """ + import os + + # Create output directory + output_dir = os.path.join( + os.path.dirname(os.path.dirname(os.path.dirname(os.path.dirname(os.path.dirname(__file__))))), + "rendered_images", + scene_id + ) + os.makedirs(output_dir, exist_ok=True) + + # Save image + filename = f"{camera_id}_{timestamp_us}.jpg" + filepath = os.path.join(output_dir, filename) + + success = cv2.imwrite(filepath, image) + if success: + logger.debug(f"Saved rendered image: {filepath}") + else: + logger.warning(f"Failed to save rendered image: {filepath}") + + def _save_panorama_view( + self, + cameras_dict: dict, + scene_id: str, + timestamp_us: int, + target_size: tuple = (640, 360) + ) -> None: + """ + Save a 3x3 panorama view combining all 8 cameras with center black. + + Layout: + CAM_L0 CAM_F0 CAM_R0 + CAM_L1 BLACK CAM_R1 + CAM_L2 CAM_B0 CAM_R2 + + Args: + cameras_dict: Dictionary of camera images from renderer + scene_id: Scene ID for output directory + timestamp_us: Timestamp for filename + target_size: Size to resize each camera view (width, height) + """ + import os + + # Camera layout mapping (3x3 grid) + layout = [ + ['CAM_L0', 'CAM_F0', 'CAM_R0'], + ['CAM_L1', 'BLACK', 'CAM_R1'], + ['CAM_L2', 'CAM_B0', 'CAM_R2'] + ] + + # Create black placeholder + black_image = np.zeros((target_size[1], target_size[0], 3), dtype=np.uint8) + + # Build panorama row by row + rows = [] + for row_cameras in layout: + row_images = [] + for camera_id in row_cameras: + if camera_id == 'BLACK': + row_images.append(black_image) + elif camera_id in cameras_dict and 'image' in cameras_dict[camera_id]: + # Resize camera image to target size + img = cameras_dict[camera_id]['image'] + resized = cv2.resize(img, target_size, interpolation=cv2.INTER_LINEAR) + row_images.append(resized) + else: + # Missing camera - use black placeholder + logger.warning(f"Camera {camera_id} not found for panorama view") + row_images.append(black_image) + + # Concatenate images horizontally + row_image = np.hstack(row_images) + rows.append(row_image) + + # Concatenate all rows vertically + panorama = np.vstack(rows) + + # Save panorama + output_dir = os.path.join( + os.path.dirname(os.path.dirname(os.path.dirname(os.path.dirname(os.path.dirname(__file__))))), + "rendered_images", + scene_id + ) + os.makedirs(output_dir, exist_ok=True) + + filename = f"panorama_{timestamp_us}.jpg" + filepath = os.path.join(output_dir, filename) + + success = cv2.imwrite(filepath, panorama) + if success: + logger.info(f"Saved panorama view ({panorama.shape[1]}x{panorama.shape[0]}): {filepath}") + else: + logger.warning(f"Failed to save panorama view: {filepath}") + + def _shut_down(self) -> None: + """Internal shutdown callback.""" + self.server.stop(0) \ No newline at end of file diff --git a/src/runtime/alpasim_runtime/services/sensorsim_service.py b/src/runtime/alpasim_runtime/services/sensorsim_service.py index 6845c737..b4bdcf66 100644 --- a/src/runtime/alpasim_runtime/services/sensorsim_service.py +++ b/src/runtime/alpasim_runtime/services/sensorsim_service.py @@ -21,6 +21,7 @@ PosePair, RGBRenderRequest, RGBRenderReturn, + ShutterType, ) from alpasim_grpc.v0.sensorsim_pb2_grpc import SensorsimServiceStub from alpasim_runtime.camera_catalog import CameraCatalog @@ -81,7 +82,66 @@ async def get_available_cameras( ) -> list[AvailableCamerasReturn.AvailableCamera]: """Fetch available cameras for `scene_id`, skipping RPC in skip mode.""" if self.skip: - return [] + logger.info("Skip mode: sensorsim returning fake CAM") + # In skip mode, return fake cameras from extra_cameras config + # so that merge_local_and_sensorsim_cameras can work properly + local_overrides = self._camera_catalog.get_local_override_cameras() + fake_cameras = [] + for cfg in local_overrides: + # Create a minimal AvailableCamera from config + # If config is complete, use it; otherwise create a minimal one + # that will be filled in by merge_local_and_sensorsim_cameras + camera = AvailableCamerasReturn.AvailableCamera( + logical_id=cfg.logical_id, + ) + # If config has all required fields, create a complete camera + if ( + cfg.rig_to_camera is not None + and cfg.intrinsics is not None + and cfg.resolution_hw is not None + and cfg.shutter_type is not None + ): + # Create camera definition from config and convert to proto + from alpasim_runtime.camera_catalog import CameraDefinition + + camera_def = CameraDefinition.from_config(cfg) + camera = camera_def.as_proto() + else: + # Create minimal camera with placeholder values + # These will be overridden by merge_local_and_sensorsim_cameras + camera.intrinsics.logical_id = cfg.logical_id + camera.intrinsics.resolution_h = cfg.resolution_hw[0] if cfg.resolution_hw else 1080 + camera.intrinsics.resolution_w = cfg.resolution_hw[1] if cfg.resolution_hw else 1920 + # Set shutter_type with default fallback + try: + camera.intrinsics.shutter_type = ShutterType.Value( + cfg.shutter_type or "GLOBAL" + ) + except ValueError: + camera.intrinsics.shutter_type = ShutterType.GLOBAL + # Set minimal intrinsics (opencv_pinhole with default values) + # This is required for CameraDefinition.from_proto to work + if cfg.intrinsics is None: + pinhole = camera.intrinsics.opencv_pinhole_param + pinhole.focal_length_x = camera.intrinsics.resolution_w + pinhole.focal_length_y = camera.intrinsics.resolution_h + pinhole.principal_point_x = camera.intrinsics.resolution_w / 2.0 + pinhole.principal_point_y = camera.intrinsics.resolution_h / 2.0 + # Set default rig_to_camera (identity) + camera.rig_to_camera.quat.w = 1.0 + if cfg.rig_to_camera is not None: + camera.rig_to_camera.vec.x = cfg.rig_to_camera.translation_m[0] + camera.rig_to_camera.vec.y = cfg.rig_to_camera.translation_m[1] + camera.rig_to_camera.vec.z = cfg.rig_to_camera.translation_m[2] + camera.rig_to_camera.quat.x = cfg.rig_to_camera.rotation_xyzw[0] + camera.rig_to_camera.quat.y = cfg.rig_to_camera.rotation_xyzw[1] + camera.rig_to_camera.quat.z = cfg.rig_to_camera.rotation_xyzw[2] + camera.rig_to_camera.quat.w = cfg.rig_to_camera.rotation_xyzw[3] + fake_cameras.append(camera) + logger.info( + f"Skip mode: returning {len(fake_cameras)} fake cameras from extra_cameras config" + ) + return fake_cameras if scene_id in self._available_cameras: return self._copy_available_cameras(self._available_cameras[scene_id]) @@ -218,6 +278,20 @@ def trajectory_to_pose_pair( delta=definition.rig_to_camera, ) + # Create ego_pose (ego vehicle pose without rig_to_camera transform) + # This is used by MTGS renderer which needs the actual ego position + ego_pose = trajectory_to_pose_pair( + ego_trajectory, + delta=None, # No rig_to_camera transform for ego pose + ) + + # Get rig_to_camera as grpc Pose for MTGS renderer + rig_to_camera_pose = ( + definition.rig_to_camera.as_grpc_pose() + if definition.rig_to_camera is not None + else None + ) + return RGBRenderRequest( scene_id=scene_id, resolution_h=camera.render_resolution_hw[0], @@ -226,6 +300,8 @@ def trajectory_to_pose_pair( frame_start_us=start_us, frame_end_us=end_us, sensor_pose=sensor_pose, + ego_pose=ego_pose, # Add ego_pose for MTGS renderer + rig_to_camera=rig_to_camera_pose, # Add rig_to_camera for MTGS dynamic_objects=dynamic_objects, image_format=image_format, image_quality=95, @@ -277,13 +353,15 @@ async def aggregated_render( ) images_with_metadata = [] - for rgb_response in response.rgb_responses: + # Match responses with requests to get metadata (timestamps, camera_id) + # RGBRenderReturn only contains image_bytes, so we need to get metadata from the request + for rgb_request, rgb_response in zip(request.rgb_requests, response.rgb_returns): images_with_metadata.append( ImageWithMetadata( - start_timestamp_us=rgb_response.start_timestamp_us, - end_timestamp_us=rgb_response.end_timestamp_us, + start_timestamp_us=rgb_request.frame_start_us, + end_timestamp_us=rgb_request.frame_end_us, image_bytes=rgb_response.image_bytes, - camera_logical_id=rgb_response.camera_logical_id, + camera_logical_id=rgb_request.camera_intrinsics.logical_id, ) ) diff --git a/src/runtime/alpasim_runtime/simulate/__main__.py b/src/runtime/alpasim_runtime/simulate/__main__.py index 35053768..6daf20e0 100644 --- a/src/runtime/alpasim_runtime/simulate/__main__.py +++ b/src/runtime/alpasim_runtime/simulate/__main__.py @@ -67,7 +67,19 @@ def create_arg_parser() -> argparse.ArgumentParser: # we split user and network config files because the latter is commonly auto-generated by kubernetes parser.add_argument("--user-config", type=str, required=True) parser.add_argument("--network-config", type=str, required=True) - parser.add_argument("--usdz-glob", type=str, required=True) + + # Data source: either USDZ glob or trajdata config (mutually exclusive) + data_source_group = parser.add_mutually_exclusive_group(required=True) + data_source_group.add_argument( + "--usdz-glob", + type=str, + help="Glob pattern for USDZ files (e.g., 'data/**/*.usdz')" + ) + data_source_group.add_argument( + "--trajdata-config", + type=str, + help="Path to JSON/YAML file containing trajdata dataset configuration" + ) parser.add_argument( "--log-dir", type=str, diff --git a/src/runtime/alpasim_runtime/worker/ipc.py b/src/runtime/alpasim_runtime/worker/ipc.py index 0bf8bbcf..d15c1644 100644 --- a/src/runtime/alpasim_runtime/worker/ipc.py +++ b/src/runtime/alpasim_runtime/worker/ipc.py @@ -107,8 +107,9 @@ class WorkerArgs: result_queue: Queue # Queue[JobResult] allocations: ServiceAllocations # Pre-computed service allocations for this worker user_config_path: str # Needed for user config (scenarios, endpoints, etc.) - usdz_glob: str log_dir: str # Root directory for outputs (asl/, metrics/, txt-logs/) + usdz_glob: str | None = None + trajdata_config_path: str | None = None # For orphan detection in subprocess mode. None disables detection (inline mode). parent_pid: Optional[int] = None # Shared RPC tracking for global queue depth metrics across processes diff --git a/src/runtime/alpasim_runtime/worker/main.py b/src/runtime/alpasim_runtime/worker/main.py index 015bf504..34f33b38 100644 --- a/src/runtime/alpasim_runtime/worker/main.py +++ b/src/runtime/alpasim_runtime/worker/main.py @@ -184,7 +184,8 @@ async def worker_async_main(args: WorkerArgs) -> None: dispatcher = await Dispatcher.create( user_config=user_config, allocations=args.allocations, - usdz_glob=args.usdz_glob, + usdz_glob=getattr(args, 'usdz_glob', None), + trajdata_config_path=getattr(args, 'trajdata_config_path', None), asl_dir=asl_dir, ) diff --git a/src/runtime/alpasim_runtime/worker/pool.py b/src/runtime/alpasim_runtime/worker/pool.py index 39de0ebc..a1b1d817 100644 --- a/src/runtime/alpasim_runtime/worker/pool.py +++ b/src/runtime/alpasim_runtime/worker/pool.py @@ -227,7 +227,8 @@ async def _run_inline_worker( result_queue=result_queue, allocations=allocations, user_config_path=args.user_config, - usdz_glob=args.usdz_glob, + usdz_glob=getattr(args, 'usdz_glob', None), + trajdata_config_path=getattr(args, 'trajdata_config', None), log_dir=log_dir, parent_pid=None, # Disable orphan detection for inline mode ) @@ -300,7 +301,8 @@ async def _run_subprocess_workers( result_queue=result_queue, allocations=all_allocations[worker_id], user_config_path=args.user_config, - usdz_glob=args.usdz_glob, + usdz_glob=getattr(args, 'usdz_glob', None), + trajdata_config_path=getattr(args, 'trajdata_config', None), parent_pid=parent_pid, log_dir=log_dir, shared_rpc_tracking=shared_rpc_tracking, diff --git a/src/utils/alpasim_utils/artifact.py b/src/utils/alpasim_utils/artifact.py index db91d8c7..fcaca9c6 100644 --- a/src/utils/alpasim_utils/artifact.py +++ b/src/utils/alpasim_utils/artifact.py @@ -238,8 +238,12 @@ def map(self) -> Optional[VectorMap]: # Try loading map data map_loaded = False with zipfile.ZipFile(self.source, "r") as zip_file: - # Try loading map from xodr - if self._load_xodr_map(zip_file): + # Try loading map from protobuf (preferred, directly from VectorMap) + if self._load_pb_map(zip_file): + map_loaded = True + logger.info("Successfully loaded map from protobuf") + # Fallback to XODR if protobuf not available + elif self._load_xodr_map(zip_file): map_loaded = True logger.info("Successfully loaded map from XODR") @@ -260,6 +264,43 @@ def map(self) -> Optional[VectorMap]: self._attempted_map_load = True return self._map + def _load_pb_map(self, zip_file: zipfile.ZipFile) -> bool: + """Load map from protobuf file. + + Args: + zip_file: Open ZipFile instance + + Returns: + True if map was successfully loaded, False otherwise + """ + try: + # Open protobuf file + with zip_file.open("map.pb", "r") as pb_file: + pb_bytes = pb_file.read() + + # Parse protobuf + if VectorMap is None: + logger.warning("VectorMap is not available, cannot load protobuf map") + return False + + import trajdata.proto.vectorized_map_pb2 as map_proto + + vec_map_proto = map_proto.VectorizedMap() + vec_map_proto.ParseFromString(pb_bytes) + + # Convert from protobuf to VectorMap + # Note: We use default parameters (incl_road_lanes=True, etc.) + # which matches the typical usage in trajdata + self._map = VectorMap.from_proto(vec_map_proto) + + return True + except (KeyError, FileNotFoundError) as e: + logger.debug(f"Could not load protobuf map: {e}") + return False + except Exception as e: + logger.warning(f"Failed to load protobuf map: {e}") + return False + def _load_xodr_map(self, zip_file: zipfile.ZipFile) -> bool: """Load map from XODR file. diff --git a/src/utils/alpasim_utils/data_source_loader.py b/src/utils/alpasim_utils/data_source_loader.py new file mode 100644 index 00000000..4242ed08 --- /dev/null +++ b/src/utils/alpasim_utils/data_source_loader.py @@ -0,0 +1,103 @@ +# SPDX-License-Identifier: Apache-2.0 +# Copyright (c) 2025 NVIDIA Corporation + +""" +Unified data source loader: supports loading data from USDZ or trajdata. +""" + +from __future__ import annotations + +import json +import logging +from pathlib import Path +from typing import Optional + +from alpasim_utils.artifact import Artifact +from alpasim_utils.scene_data_source import SceneDataSource + +logger = logging.getLogger(__name__) + +try: + from trajdata.dataset import UnifiedDataset + from alpasim_utils.trajdata_data_source import discover_from_trajdata_dataset + TRAJDATA_AVAILABLE = True +except ImportError as e: + TRAJDATA_AVAILABLE = False + UnifiedDataset = None + logger.debug(f"trajdata not available: {e}. Trajdata loading will be disabled.") + + +def load_data_sources( + usdz_glob: Optional[str] = None, + trajdata_config_path: Optional[str] = None, + smooth_trajectories: bool = True, +) -> dict[str, SceneDataSource]: + """ + Unified data source loading function that supports loading from USDZ or trajdata. + + Args: + usdz_glob: Glob pattern for USDZ files (mutually exclusive with trajdata_config_path) + trajdata_config_path: Path to JSON/YAML file containing trajdata configuration + smooth_trajectories: Whether to smooth trajectories + + Returns: + dict[scene_id, SceneDataSource] + + Raises: + ValueError: If both or neither of usdz_glob and trajdata_config_path are provided + ImportError: If trajdata is not installed but trajdata_config_path is provided + """ + if usdz_glob is not None and trajdata_config_path is not None: + raise ValueError( + "Cannot specify both usdz_glob and trajdata_config_path. Choose one." + ) + + if usdz_glob is None and trajdata_config_path is None: + raise ValueError( + "Either usdz_glob or trajdata_config_path must be provided." + ) + + if usdz_glob is not None: + # Load from USDZ files + logger.info(f"Loading artifacts from USDZ files: {usdz_glob}") + artifacts = Artifact.discover_from_glob( + usdz_glob, smooth_trajectories=smooth_trajectories + ) + logger.info(f"Loaded {len(artifacts)} scenes from USDZ files") + return artifacts + + # Load from trajdata + if not TRAJDATA_AVAILABLE: + raise ImportError( + "trajdata is not installed. Install trajdata to use trajdata_config_path option." + ) + + logger.info(f"Loading artifacts from trajdata config: {trajdata_config_path}") + + # Load config file + config_path = Path(trajdata_config_path) + if not config_path.exists(): + raise FileNotFoundError(f"Trajdata config file not found: {config_path}") + + with open(config_path, 'r') as f: + if config_path.suffix.lower() in ['.yaml', '.yml']: + import yaml + config = yaml.safe_load(f) + else: + # Assume JSON + config = json.load(f) + + # Extract scene_indices if provided + scene_indices = config.pop("scene_indices", None) + + # Create UnifiedDataset + dataset = UnifiedDataset(**config) + + # Discover data sources + artifacts = discover_from_trajdata_dataset( + dataset=dataset, + scene_indices=scene_indices, + smooth_trajectories=smooth_trajectories, + ) + logger.info(f"Loaded {len(artifacts)} scenes from trajdata dataset") + return artifacts diff --git a/src/utils/alpasim_utils/geometry_utils.py b/src/utils/alpasim_utils/geometry_utils.py new file mode 100644 index 00000000..5b6796de --- /dev/null +++ b/src/utils/alpasim_utils/geometry_utils.py @@ -0,0 +1,223 @@ +import numbers +import math +import json +from pathlib import Path +from dataclasses import dataclass +from typing import List +from enum import IntEnum + +import numpy as np +import numpy.typing as npt +from nuplan.common.actor_state.state_representation import StateSE2 + +class SE2Index(IntEnum): + """Index mapping for state se2 (x,y,θ) arrays.""" + + X = 0 + Y = 1 + HEADING = 2 + +def normalize_angle(angle): + """ + Map a angle in range [-π, π] + :param angle: any angle as float + :return: normalized angle + """ + return np.arctan2(np.sin(angle), np.cos(angle)) + +def convert_absolute_to_relative_se2_array( + origin: StateSE2, state_se2_array: npt.NDArray[np.float64] +) -> npt.NDArray[np.float64]: + """ + Converts an StateSE2 array from global to relative coordinates. + :param origin: origin pose of relative coords system + :param state_se2_array: array of SE2 states with (x,y,θ) in last dim + :return: SE2 coords array in relative coordinates + """ + assert len(SE2Index) == state_se2_array.shape[-1] + + theta = -origin.heading + origin_array = np.array([[origin.x, origin.y, origin.heading]], dtype=np.float64) + + R = np.array([[np.cos(theta), -np.sin(theta)], [np.sin(theta), np.cos(theta)]]) + + points_rel = state_se2_array - origin_array + points_rel[..., :2] = points_rel[..., :2] @ R.T + points_rel[:, 2] = normalize_angle(points_rel[:, 2]) + + return points_rel + +@dataclass(frozen=True) +class Sim2: + """Similarity(2) lie group object. + + Args: + R: array of shape (2x2) representing 2d rotation matrix + t: array of shape (2,) representing 2d translation + s: scaling factor + """ + + R: npt.NDArray[np.float64] + t: npt.NDArray[np.float64] + s: float + + def __post_init__(self) -> None: + """Check validity of rotation, translation, and scale arguments. + + Raises: + ValueError: If `R` is not shape (3,3), `t` is not shape (2,), + or `s` is not a numeric type. + ZeroDivisionError: If `s` is close or equal to zero. + """ + assert self.R.shape == (2, 2) + assert self.t.shape == (2,) + + if not isinstance(self.s, numbers.Number): + raise ValueError("Scale `s` must be a numeric type!") + if math.isclose(self.s, 0.0): + raise ZeroDivisionError( + "3x3 matrix formation would require division by zero" + ) + + def __repr__(self) -> str: + """Return a human-readable string representation of the class.""" + trans = np.round(self.t, 2) + return ( + f"Angle (deg.): {self.theta_deg:.1f}, Trans.: {trans}, Scale: {self.s:.1f}" + ) + + def __eq__(self, other: object) -> bool: + """Check for equality with other Sim(2) object.""" + if not isinstance(other, Sim2): + return False + + if not np.isclose(self.scale, other.scale): + return False + + if not np.allclose(self.rotation, other.rotation): + return False + + if not np.allclose(self.translation, other.translation): + return False + + return True + + @property + def theta_deg(self) -> float: + """Recover the rotation angle `theta` (in degrees) from the 2d rotation matrix. + + Note: the first column of the rotation matrix R provides sine and cosine of theta, + since R is encoded as [c,-s] + [s, c] + + We use the following identity: tan(theta) = s/c = (opp/hyp) / (adj/hyp) = opp/adj + + Returns: + Rotation angle from the 2d rotation matrix. + """ + c, s = self.R[0, 0], self.R[1, 0] + theta_rad = np.arctan2(s, c) + return float(np.rad2deg(theta_rad)) + + @property + def rotation(self) -> npt.NDArray[np.float64]: + """Return the 2x2 rotation matrix.""" + return self.R + + @property + def translation(self) -> npt.NDArray[np.float64]: + """Return the (2,) translation vector.""" + return self.t + + @property + def scale(self) -> float: + """Return the scale.""" + return self.s + + @property + def matrix(self) -> npt.NDArray[np.float64]: + """Calculate 3*3 matrix group equivalent.""" + T = np.zeros((3, 3)) + T[:2, :2] = self.R + T[:2, 2] = self.t + T[2, 2] = 1 / self.s + return T + + def compose(self, S): + """Composition with another Sim2. + + This can be understood via block matrix multiplication, if self is parameterized as (R1,t1,s1) + and if `S` is parameterized as (R2,t2,s2): + + [R1 t1] [R2 t2] [R1 @ R2 R1@t2 + t1/s2] + [0 1/s1] @ [0 1/s2] = [ 0 1/(s1*s2) ] + + Args: + S: Similarity(2) transformation. + + Returns: + Composed Similarity(2) transformation. + """ + # fmt: off + return Sim2( + R=self.R @ S.R, + t=self.R @ S.t + ((1.0 / S.s) * self.t), + s=self.s * S.s + ) + # fmt: on + + def inverse(self): + """Return the inverse.""" + Rt = self.R.T + sRt = -Rt @ (self.s * self.t) + return Sim2(Rt, sRt, 1.0 / self.s) + + def transform_from(self, points_xy): + """Transform point cloud from reference frame a to b. + + If the points are in frame A, and our Sim(3) transform is defines as bSa, then we get points + back in frame B: + p_b = bSa * p_a + Action on a point p is s*(R*p+t). + + Args: + points_xy: Nx2 array representing 2d points in frame A. + + Returns: + Nx2 array representing 2d points in frame B. + + Raises: + ValueError: if `points_xy` isn't in R^2. + """ + if not points_xy.ndim == 2: + raise ValueError("Input points are not 2-dimensional.") + assert points_xy.shape[1] == 2 + # (2,2) x (2,N) + (2,1) = (2,N) -> transpose + transformed_point_cloud = (points_xy @ self.R.T) + self.t + + # now scale points + return transformed_point_cloud * self.s + + @classmethod + def from_json(cls, json_fpath: Path): + """Generate class inst. from a JSON file containing Sim(2) parameters as flattened matrices (row-major).""" + with json_fpath.open("r") as f: + json_data = json.load(f) + + R = np.array(json_data["R"]).reshape(2, 2) + t = np.array(json_data["t"]).reshape(2) + s = float(json_data["s"]) + return cls(R, t, s) + + @classmethod + def from_matrix(cls, T: npt.NDArray[np.float64]): + """Generate class instance from a 3x3 Numpy matrix.""" + if np.isclose(T[2, 2], 0.0): + raise ZeroDivisionError( + "Sim(2) scale calculation would lead to division by zero." + ) + + R = T[:2, :2] + t = T[:2, 2] + s = 1 / T[2, 2] + return cls(R, t, s) diff --git a/src/utils/alpasim_utils/mtgs_artifact_adapter.py b/src/utils/alpasim_utils/mtgs_artifact_adapter.py new file mode 100644 index 00000000..4d3c35af --- /dev/null +++ b/src/utils/alpasim_utils/mtgs_artifact_adapter.py @@ -0,0 +1,471 @@ +# SPDX-License-Identifier: Apache-2.0 +# Copyright (c) 2025 NVIDIA Corporation + +""" +Adapter for converting alpasim data formats to MTGS renderer formats. + +This module provides conversion utilities between: +- alpasim gRPC messages (RGBRenderRequest, PosePair, etc.) +- MTGS RenderState and camera configurations +""" + +from __future__ import annotations + +import logging +from typing import Any, Dict, Optional + +import numpy as np +from pyquaternion import Quaternion + +from alpasim_grpc.v0.common_pb2 import Pose as GrpcPose +from alpasim_grpc.v0.sensorsim_pb2 import ( + AvailableCamerasReturn, + CameraSpec, + DynamicObject, + RGBRenderRequest, +) +from alpasim_utils.qvec import QVec +from alpasim_utils.scene_data_source import SceneDataSource + +logger = logging.getLogger(__name__) + + +# ================================================================================== +# Nuplan SDK Standard Camera/Lidar Extrinsics (Fixed for all Pacifica vehicles) +# ================================================================================== +# These values are used to override potentially incorrect values from video_scene_dict.pkl +# All sensor2ego transformations are relative to the rear axle (ego coordinate origin). + +# LIDAR_TOP to ego (rear axle) transformation +NUPLAN_LIDAR2EGO = { + 'translation': np.array([1.5185133218765259, 0.0, 1.6308990716934204]), + 'rotation': np.array([-0.0016505558783280307, -0.00023289146777086609, + 0.003725490480134295, 0.9999916710390838]), # [x, y, z, w] +} + +# Flag to enable/disable override (set to True to use Nuplan standard values) +USE_NUPLAN_STANDARD_EXTRINSICS = True + +logger.info(f"USE_NUPLAN_STANDARD_EXTRINSICS: {USE_NUPLAN_STANDARD_EXTRINSICS}") +if USE_NUPLAN_STANDARD_EXTRINSICS: + logger.info("Will override sensor2ego from video_scene_dict with values from pkl (which are already correct)") + logger.info("Will override lidar2ego with Nuplan standard values") + + +def grpc_pose_to_quaternion_and_translation(grpc_pose: GrpcPose) -> tuple[np.ndarray, np.ndarray]: + """ + Convert gRPC Pose to quaternion and translation. + + Args: + grpc_pose: gRPC Pose message + + Returns: + Tuple of (quaternion [w, x, y, z], translation [x, y, z]) + """ + quat = np.array([grpc_pose.quat.w, grpc_pose.quat.x, grpc_pose.quat.y, grpc_pose.quat.z]) + trans = np.array([grpc_pose.vec.x, grpc_pose.vec.y, grpc_pose.vec.z]) + return quat, trans + + +def camera_spec_to_worldengine_format( + camera_spec: CameraSpec, rig_to_camera: Optional[GrpcPose] = None +) -> Dict: + """ + Convert alpasim CameraSpec to MTGS camera format. + + Args: + camera_spec: CameraSpec from gRPC message + rig_to_camera: Optional rig_to_camera pose transformation + + Returns: + Dictionary in MTGS camera format: + { + "channel": str, + "sensor2ego_rotation": np.ndarray (quaternion), + "sensor2ego_translation": np.ndarray ([x, y, z]), + "intrinsic": np.ndarray (3x3), + "distortion": np.ndarray, + "height": int, + "width": int + } + """ + camera_dict = { + "channel": camera_spec.logical_id, + "height": camera_spec.resolution_h, + "width": camera_spec.resolution_w, + } + + # Extract intrinsic parameters + if camera_spec.HasField("opencv_pinhole_param"): + param = camera_spec.opencv_pinhole_param + intrinsic = np.array([ + [param.focal_length_x, 0, param.principal_point_x], + [0, param.focal_length_y, param.principal_point_y], + [0, 0, 1], + ], dtype=np.float32) + + # Combine radial and tangential distortion + radial = list(param.radial_coeffs) if param.radial_coeffs else [] + tangential = list(param.tangential_coeffs) if param.tangential_coeffs else [] + # Pad to at least 5 elements (k1, k2, p1, p2, k3) + distortion = (radial + [0.0] * (5 - len(radial)))[:5] + if len(tangential) >= 2: + distortion[2:4] = tangential[:2] + distortion = np.array(distortion, dtype=np.float32) + + camera_dict["intrinsic"] = intrinsic + camera_dict["distortion"] = distortion + elif camera_spec.HasField("opencv_fisheye_param"): + param = camera_spec.opencv_fisheye_param + intrinsic = np.array([ + [param.focal_length_x, 0, param.principal_point_x], + [0, param.focal_length_y, param.principal_point_y], + [0, 0, 1], + ], dtype=np.float32) + distortion = np.array(list(param.radial_coeffs) if param.radial_coeffs else [0.0] * 4, dtype=np.float32) + camera_dict["intrinsic"] = intrinsic + camera_dict["distortion"] = distortion + else: + logger.warning(f"Unsupported camera parameter type for {camera_spec.logical_id}") + # Default intrinsic matrix + camera_dict["intrinsic"] = np.eye(3, dtype=np.float32) + camera_dict["distortion"] = np.zeros(5, dtype=np.float32) + + # Extract sensor2ego transformation + if rig_to_camera is not None: + # rig_to_camera is actually camera_to_rig in the proto (see comment in proto) + # We need camera_to_ego, which is the inverse of rig_to_camera + quat, trans = grpc_pose_to_quaternion_and_translation(rig_to_camera) + # Invert the transformation + q_inv = Quaternion(quat[0], quat[1], quat[2], quat[3]).inverse + camera_dict["sensor2ego_rotation"] = np.array([q_inv.w, q_inv.x, q_inv.y, q_inv.z]) + # Translation inversion: t' = -R^T * t + rot_matrix = q_inv.rotation_matrix + camera_dict["sensor2ego_translation"] = -rot_matrix.T @ trans + else: + # Default: identity transformation + camera_dict["sensor2ego_rotation"] = np.array([1.0, 0.0, 0.0, 0.0]) + camera_dict["sensor2ego_translation"] = np.array([0.0, 0.0, 0.0]) + + return camera_dict + + +def pose_pair_to_agent_state( + start_pose: GrpcPose, end_pose: GrpcPose, use_start: bool = True +) -> np.ndarray: + """ + Convert PosePair to MTGS agent_state format [x, y, z, 0, 0, heading]. + + Args: + start_pose: Start pose from PosePair + end_pose: End pose from PosePair + use_start: If True, use start_pose; otherwise use end_pose + + Returns: + numpy array [x, y, z, 0, 0, heading] where heading is yaw angle in radians + """ + pose = start_pose if use_start else end_pose + quat, trans = grpc_pose_to_quaternion_and_translation(pose) + + # Extract yaw from quaternion + q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + yaw = q.yaw_pitch_roll[0] + + # MTGS format: [x, y, z, 0, 0, heading] + return np.array([trans[0], trans[1], trans[2], 0.0, 0.0, yaw], dtype=np.float64) + + +def rgb_render_request_to_render_state( + request: RGBRenderRequest, + asset_manager: Optional[Any] = None, +) -> Dict: + """ + Convert RGBRenderRequest to MTGS RenderState format. + + Simplified version: Only extracts scene_id, AGENT_STATE, and TIMESTAMP from request. + Camera information is loaded from asset_manager's video_scene_dict (pkl file). + + Args: + request: RGBRenderRequest from gRPC (only scene_id, agent_state, timestamp are used) + data_source: Optional SceneDataSource (used for backward compatibility with sensor_pose) + asset_manager: MTGSAssetManager for accessing video_scene_dict (required for cameras) + + Returns: + Dictionary compatible with MTGS RenderState: + { + "timestamp": int (microseconds), + "agent_state": Dict[str, np.ndarray], # {object_id: [x, y, z, 0, 0, heading]} + "cameras": Dict[str, Dict], # {camera_name: camera_config} - loaded from pkl + } + """ + # Extract timestamp + timestamp = request.frame_start_us + + # Extract ego agent state + # Priority: 1) ego_pose (new field), 2) sensor_pose (backward compatibility) + agent_states = {} + if request.HasField("ego_pose"): + # Use ego_pose directly (preferred for MTGS renderer) + ego_state = pose_pair_to_agent_state( + request.ego_pose.start_pose, + request.ego_pose.end_pose, + use_start=True + ) + agent_states["ego"] = ego_state + elif request.HasField("sensor_pose"): + # Fallback: use sensor_pose as ego_pose (may be inaccurate but allows testing) + logger.warning( + "ego_pose not found in request, using sensor_pose as fallback. " + "Consider updating Runtime to send ego_pose field." + ) + ego_state = pose_pair_to_agent_state( + request.sensor_pose.start_pose, + request.sensor_pose.end_pose, + use_start=True + ) + agent_states["ego"] = ego_state + else: + raise ValueError("RGBRenderRequest must contain either ego_pose or sensor_pose") + + # Extract traffic agent states from dynamic_objects + for dyn_obj in request.dynamic_objects: + track_id = dyn_obj.track_id + agent_state = pose_pair_to_agent_state( + dyn_obj.pose_pair.start_pose, + dyn_obj.pose_pair.end_pose, + use_start=True + ) + agent_states[track_id] = agent_state + + # Load camera configuration from asset_manager's video_scene_dict (pkl file) + cameras = {} + if asset_manager is not None and hasattr(asset_manager, 'video_scene_dict') and asset_manager.video_scene_dict: + + video_info_raw = asset_manager.video_scene_dict + + # Handle nested structure: video_scene_dict may be {scene_id: {frame_infos, ...}} + # or directly {frame_infos, ...} + video_info = video_info_raw + if isinstance(video_info_raw, dict) and 'frame_infos' not in video_info_raw: + # Nested structure - get the first (and usually only) scene data + first_key = next(iter(video_info_raw.keys()), None) + if first_key and isinstance(video_info_raw[first_key], dict): + video_info = video_info_raw[first_key] + + if 'frame_infos' not in video_info or len(video_info['frame_infos']) == 0: + logger.warning("No frame_infos found in video_scene_dict") + else: + frame_info = video_info['frame_infos'][0] + if 'cams' not in frame_info: + logger.warning("No 'cams' found in frame_infos[0]") + else: + for cam_name, mtgs_cam_info in frame_info['cams'].items(): + # Extract intrinsic and distortion (prefer colmap_param if available) + # These are from colmap optimization and should be used as-is + if 'colmap_param' in mtgs_cam_info: + intrinsic = np.array(mtgs_cam_info['colmap_param']['cam_intrinsic']) + distortion = np.array(mtgs_cam_info['colmap_param']['distortion']) + else: + intrinsic = np.array(mtgs_cam_info['cam_intrinsic']) + distortion = np.array(mtgs_cam_info['distortion']) + + # Extract sensor2ego transformation from pkl + # NOTE: Our analysis shows that sensor2ego in video_scene_dict is ALREADY correct + # (relative to rear axle, matching Nuplan SDK standard) + # So we use it directly without override + sensor2ego_rotation = mtgs_cam_info['sensor2ego_rotation'] + if isinstance(sensor2ego_rotation, Quaternion): + sensor2ego_rotation = sensor2ego_rotation.elements + else: + sensor2ego_rotation = np.array(sensor2ego_rotation) + + sensor2ego_translation = np.array(mtgs_cam_info['sensor2ego_translation']) + + # Get resolution (default to 1080x1920) + height = mtgs_cam_info.get('height', 1080) + width = mtgs_cam_info.get('width', 1920) + + cameras[cam_name] = { + 'channel': cam_name, + 'sensor2ego_rotation': sensor2ego_rotation, + 'sensor2ego_translation': sensor2ego_translation, + 'intrinsic': intrinsic, + 'distortion': distortion, + 'height': height, + 'width': width, + } + else: + logger.warning("asset_manager or video_scene_dict not available, cameras will be empty") + + # Setup lidar parameters with Nuplan standard values + # The key issue: video_scene_dict may have lidar2ego=[0,0,0], which is incorrect + # We override it with the standard Nuplan value here + lidar_params = {} + if USE_NUPLAN_STANDARD_EXTRINSICS: + lidar_params = { + 'channel': 'LIDAR_TOP', + 'sensor2ego_translation': NUPLAN_LIDAR2EGO['translation'], + 'sensor2ego_rotation': NUPLAN_LIDAR2EGO['rotation'], + } + + render_state = { + "timestamp": timestamp, + "agent_state": agent_states, + "cameras": cameras, + "lidar": lidar_params, + } + + return render_state + + +def get_available_cameras_from_data_source( + asset_manager: Optional[Any] = None, +) -> list[AvailableCamerasReturn.AvailableCamera]: + """ + Extract available cameras from SceneDataSource or video_info. + + If asset_manager.video_scene_dict is available, extract cameras from pkl file. + Otherwise, create default NuPlan cameras. + + Args: + data_source: SceneDataSource instance + asset_manager: Optional asset manager with video_scene_dict + + Returns: + List of AvailableCamera messages + """ + import numpy as np + from pyquaternion import Quaternion + + cameras = [] + + # Try to get cameras from video_info (pkl file) + video_info = None + if asset_manager is not None and hasattr(asset_manager, 'video_scene_dict') and asset_manager.video_scene_dict: + try: + # video_scene_dict is a dict, get the first video_info + video_scene_dict = asset_manager.video_scene_dict + if isinstance(video_scene_dict, dict): + video_info = list(video_scene_dict.values())[0] + else: + video_info = video_scene_dict + except Exception as e: + logger.warning(f"Failed to get video_info from asset_manager: {e}") + + if video_info and 'frame_infos' in video_info and len(video_info['frame_infos']) > 0: + # Extract cameras from video_info (pkl file) + logger.info("Extracting cameras from video_info (pkl file)") + frame_info = video_info['frame_infos'][0] + + for cam_name, cam_info in frame_info['cams'].items(): + # 1. Extract intrinsic parameters + if 'colmap_param' in cam_info: + intrinsic = np.array(cam_info['colmap_param']['cam_intrinsic']) + distortion = np.array(cam_info['colmap_param']['distortion']) + else: + intrinsic = np.array(cam_info['cam_intrinsic']) + distortion = np.array(cam_info.get('distortion', np.zeros(5))) + + # Extract focal length and principal point from intrinsic matrix + # Intrinsic matrix format: [[fx, 0, cx], [0, fy, cy], [0, 0, 1]] + focal_length_x = float(intrinsic[0, 0]) + focal_length_y = float(intrinsic[1, 1]) + principal_point_x = float(intrinsic[0, 2]) + principal_point_y = float(intrinsic[1, 2]) + + # 2. Extract extrinsic parameters (sensor2ego) + sensor2ego_rotation = cam_info['sensor2ego_rotation'] + if isinstance(sensor2ego_rotation, Quaternion): + quat_elements = sensor2ego_rotation.elements # [w, x, y, z] + else: + quat_elements = np.array(sensor2ego_rotation) + + sensor2ego_translation = np.array(cam_info['sensor2ego_translation']) + + # 3. Get resolution + height = cam_info.get('height', 1080) + width = cam_info.get('width', 1920) + + # 4. Create CameraSpec + camera_spec = CameraSpec( + logical_id=cam_name, + resolution_h=int(height), + resolution_w=int(width), + ) + + # Set pinhole intrinsics from matrix + pinhole = camera_spec.opencv_pinhole_param + pinhole.focal_length_x = focal_length_x + pinhole.focal_length_y = focal_length_y + pinhole.principal_point_x = principal_point_x + pinhole.principal_point_y = principal_point_y + + # 5. Create rig_to_camera pose + # Note: sensor2ego means ego->sensor transformation + # rig_to_camera means rig->camera transformation + # In nuPlan, ego and rig are typically the same, so we can use sensor2ego directly + # But rig_to_camera might need to be the inverse (camera->rig) + # Check your coordinate system definition! + # For now, assuming rig=ego and rig_to_camera = sensor2ego (ego->sensor = rig->camera) + + rig_to_camera = GrpcPose() + rig_to_camera.vec.x = float(sensor2ego_translation[0]) + rig_to_camera.vec.y = float(sensor2ego_translation[1]) + rig_to_camera.vec.z = float(sensor2ego_translation[2]) + rig_to_camera.quat.w = float(quat_elements[0]) # w is first element + rig_to_camera.quat.x = float(quat_elements[1]) + rig_to_camera.quat.y = float(quat_elements[2]) + rig_to_camera.quat.z = float(quat_elements[3]) + + available_camera = AvailableCamerasReturn.AvailableCamera( + intrinsics=camera_spec, + rig_to_camera=rig_to_camera, + logical_id=cam_name, + ) + cameras.append(available_camera) + + logger.info(f"Extracted {len(cameras)} cameras from video_info: {[c.logical_id for c in cameras]}") + return cameras + + # Fallback: Create default cameras if video_info is not available + logger.info("No cameras found in video_info, creating default NuPlan cameras") + default_cameras = [ + "CAM_F0", + "CAM_L0", "CAM_L1", "CAM_L2", + "CAM_R0", "CAM_R1", "CAM_R2", + "CAM_B0" + ] + + for camera_name in default_cameras: + camera_spec = CameraSpec( + logical_id=camera_name, + resolution_h=1080, + resolution_w=1920, + ) + + # Set default pinhole intrinsics + pinhole = camera_spec.opencv_pinhole_param + pinhole.focal_length_x = 1920.0 + pinhole.focal_length_y = 1080.0 + pinhole.principal_point_x = 960.0 + pinhole.principal_point_y = 560.0 + + # Create identity pose (camera at rig origin, no rotation) + rig_to_camera = GrpcPose() + rig_to_camera.vec.x = 0.0 + rig_to_camera.vec.y = 0.0 + rig_to_camera.vec.z = 0.0 + rig_to_camera.quat.w = 1.0 + rig_to_camera.quat.x = 0.0 + rig_to_camera.quat.y = 0.0 + rig_to_camera.quat.z = 0.0 + + available_camera = AvailableCamerasReturn.AvailableCamera( + intrinsics=camera_spec, + rig_to_camera=rig_to_camera, + logical_id=camera_name, + ) + cameras.append(available_camera) + + logger.info(f"Created {len(cameras)} default cameras: {[c.logical_id for c in cameras]}") + return cameras diff --git a/src/utils/alpasim_utils/scenario.py b/src/utils/alpasim_utils/scenario.py index abf18dfb..3af89f29 100644 --- a/src/utils/alpasim_utils/scenario.py +++ b/src/utils/alpasim_utils/scenario.py @@ -214,7 +214,8 @@ def load_from_json(cls, json_str: str, smooth=True) -> dict[str, Self]: timestamps_us=np.array(timestamps_us, dtype=np.uint64), poses=poses_qvec, ) - if smooth: + if smooth and len(trajectory) >= 2: + # at least 2 points are needed for csaps css = csaps.CubicSmoothingSpline( trajectory.timestamps_us / 1e6, trajectory.poses.vec3.T, # Expects time in last dimension @@ -230,6 +231,11 @@ def load_from_json(cls, json_str: str, smooth=True) -> dict[str, Self]: f"Max error in cubic spline approximation: {max_error:.6f} m for {track_id=}" ) trajectory.poses.vec3 = filtered_positions + elif smooth and len(trajectory) < 2: + logger.warning( + f"Skipping smoothing for {track_id=} with only {len(trajectory)} data point(s). " + "Smoothing requires at least 2 data points." + ) trajectories[track_id] = TrafficObject( track_id, AABB(*aabb_xyz), trajectory, is_static, track_label diff --git a/src/utils/alpasim_utils/scene_data_source.py b/src/utils/alpasim_utils/scene_data_source.py new file mode 100644 index 00000000..57c54964 --- /dev/null +++ b/src/utils/alpasim_utils/scene_data_source.py @@ -0,0 +1,78 @@ +# SPDX-License-Identifier: Apache-2.0 +# Copyright (c) 2025 NVIDIA Corporation + +""" +SceneDataSource Protocol for abstracting scene data loading. + +This Protocol allows Runtime to work with different data sources (USDZ, Nuplan, Waymo, etc.) +without being tied to a specific implementation. Any class that implements this Protocol +can be used as a data source for alpasim Runtime. +""" + +from __future__ import annotations + +from typing import Optional, Protocol, runtime_checkable + +try: + from trajdata.maps import VectorMap +except ImportError: + VectorMap = None # type: ignore + +from alpasim_utils.artifact import Metadata +from alpasim_utils.scenario import Rig, TrafficObjects + + +@runtime_checkable +class SceneDataSource(Protocol): + """ + Protocol defining the interface for scene data sources. + + Any class implementing this protocol can be used as a data source for alpasim Runtime. + This allows supporting multiple data formats (USDZ, Nuplan, Waymo, etc.) without + modifying Runtime code. + + Attributes: + scene_id: Unique identifier for the scene + """ + + scene_id: str + + @property + def rig(self) -> Rig: + """ + Get the rig (ego vehicle) trajectory and configuration. + + Returns: + Rig object containing trajectory, camera IDs, and vehicle config + """ + ... + + @property + def traffic_objects(self) -> TrafficObjects: + """ + Get traffic objects (vehicles, pedestrians, etc.) in the scene. + + Returns: + TrafficObjects dictionary mapping track_id to TrafficObject + """ + ... + + @property + def map(self) -> Optional[VectorMap]: + """ + Get the vector map for the scene. + + Returns: + VectorMap object or None if map data is not available + """ + ... + + @property + def metadata(self) -> Metadata: + """ + Get metadata about the scene. + + Returns: + Metadata object containing scene information + """ + ... diff --git a/src/utils/alpasim_utils/trajdata_artifact_converter.py b/src/utils/alpasim_utils/trajdata_artifact_converter.py new file mode 100644 index 00000000..452bde97 --- /dev/null +++ b/src/utils/alpasim_utils/trajdata_artifact_converter.py @@ -0,0 +1,821 @@ +# SPDX-License-Identifier: Apache-2.0 +# Copyright (c) 2025 NVIDIA Corporation + +""" +Conversion utilities: convert a trajdata UnifiedDataset into the alpasim Artifact format. +""" + +from __future__ import annotations + +import json +import logging +import uuid +import zipfile +from datetime import datetime +from pathlib import Path +from typing import Optional + +import numpy as np +import yaml +from scipy.spatial.transform import Rotation as R + +from alpasim_utils.artifact import Artifact, Metadata +from alpasim_utils.qvec import QVec +from alpasim_utils.scenario import AABB, CameraId, Rig, TrafficObject, TrafficObjects, VehicleConfig +from alpasim_utils.trajectory import Trajectory + +logger = logging.getLogger(__name__) + +try: + from trajdata.caching import EnvCache + from trajdata.data_structures.agent import AgentMetadata, AgentType + from trajdata.data_structures.scene_metadata import Scene + from trajdata.dataset import UnifiedDataset + from trajdata.maps import VectorMap +except ImportError: + logger.error("trajdata is required for this conversion function") + raise + + +def convert_unified_dataset_to_artifact( + dataset: UnifiedDataset, + scene_idx: int, + output_path: str, + scene_id: Optional[str] = None, + version_string: str = "trajdata_converted", + base_timestamp_us: Optional[int] = None, + include_map: bool = True, +) -> Artifact: + """ + Convert a scene from a UnifiedDataset to the Artifact format and save it as a USDZ file. + + Args: + dataset: UnifiedDataset instance. + scene_idx: Index of the scene to convert. + output_path: Output USDZ file path (must end with .usdz). + scene_id: Scene ID (if None, generated from scene.name). + version_string: Version string. + base_timestamp_us: Base timestamp (microseconds); if None, starts from 0. + include_map: Whether to include map data. + + Returns: + Artifact instance. + """ + if not output_path.endswith(".usdz"): + raise ValueError("output_path must end with .usdz") + + # 1. Get the Scene object + scene = dataset.get_scene(scene_idx) + scene_path = dataset._scene_index[scene_idx] + + # Create SceneCache + scene_cache = dataset.cache_class(dataset.cache_path, scene, dataset.augmentations) + scene_cache.set_obs_format(dataset.obs_format) + + # 2. Generate scene_id + if scene_id is None: + scene_id = f"trajdata-{scene.env_name}-{scene.name}" + + # 3. Extract full trajectories for all agents + dt = scene.dt + length_timesteps = scene.length_timesteps + + # Get all agents + all_agents = scene.agents if scene.agents else [] + + # Identify ego agent + ego_agent = next((a for a in all_agents if a.name == "ego"), None) + if ego_agent is None and len(all_agents) > 0: + # If there is no ego, use the first agent + ego_agent = all_agents[0] + logger.warning(f"No ego agent found, using first agent: {ego_agent.name}") + + # 4. Extract ego trajectory + ego_trajectory = None + ego_vehicle_config = None + if ego_agent: + ego_trajectory, ego_vehicle_config = _extract_agent_trajectory( + scene, scene_cache, ego_agent, dt, base_timestamp_us + ) + + # 5. Compute world_to_nre transform matrix (use first trajectory point as origin) + world_to_nre = np.eye(4) + if ego_trajectory and len(ego_trajectory) > 0: + # Get the position of the first trajectory point (global coordinates) + first_pose_position = ego_trajectory.poses[0].vec3 + + # Set world_to_nre matrix: use the first trajectory point as origin. + # The translation part of world_to_nre = -position of the first trajectory point. + world_to_nre[:3, 3] = -first_pose_position + + logger.info( + f"Setting world_to_nre origin at first pose: {first_pose_position}, " + f"translation: {world_to_nre[:3, 3]}" + ) + else: + logger.warning("No ego trajectory found, using identity world_to_nre matrix") + + # 6. Transform ego trajectory into local coordinates (NRE) + if ego_trajectory and len(ego_trajectory) > 0: + ego_trajectory = _transform_trajectory_to_local(ego_trajectory, world_to_nre) + logger.info( + f"Transformed ego trajectory to local coordinates. " + f"First pose: {ego_trajectory.poses[0].vec3}" + ) + + # 7. Extract trajectories of other agents (traffic objects) + traffic_objects = {} + for agent in all_agents: + if agent.name == "ego" or agent == ego_agent: + continue + + trajectory, _ = _extract_agent_trajectory( + scene, scene_cache, agent, dt, base_timestamp_us + ) + + # Filter out empty trajectories or trajectories with only 1 point (smoothing needs at least 2 points) + if trajectory is None or len(trajectory) < 2: + continue + + # Transform trajectory into local coordinates (NRE) + trajectory = _transform_trajectory_to_local(trajectory, world_to_nre) + + # Get extent of the agent + extent = agent.extent + if hasattr(extent, 'length'): + aabb = AABB(x=extent.length, y=extent.width, z=extent.height) + else: + # Default size + aabb = AABB(x=4.5, y=1.8, z=1.5) + + # Determine whether this is a static object (simple heuristic: very small velocity) + is_static = _is_static_object(trajectory) + + # Get agent type label + label_class = agent.type.name if hasattr(agent.type, 'name') else "UNKNOWN" + + traffic_objects[agent.name] = TrafficObject( + track_id=agent.name, + aabb=aabb, + trajectory=trajectory, + is_static=is_static, + label_class=label_class, + ) + + # 8. Create Rig object + rig = None + if ego_trajectory and len(ego_trajectory) > 0: + + # Extract camera information from scene.data_access_info['sensor_calibration'] + camera_ids, camera_calibrations = _extract_camera_info_from_scene( + scene, scene_id + ) + + rig = Rig( + sequence_id=scene_id, + trajectory=ego_trajectory, + camera_ids=camera_ids, + world_to_nre=world_to_nre, + vehicle_config=ego_vehicle_config, + ) + + # Store camera_calibrations on the rig object (for later writing to USDZ) + rig._camera_calibrations = camera_calibrations + + # 9. Create TrafficObjects + traffic_objects_dict = TrafficObjects(traffic_objects) + + # 10. Create Metadata + if base_timestamp_us is None: + base_timestamp_us = 0 + + time_range_start = float(base_timestamp_us) / 1e6 + time_range_end = float(base_timestamp_us + length_timesteps * dt * 1e6) / 1e6 + + # Extract camera ID list from rig (if present) + camera_id_names = [] + if rig and rig.camera_ids: + camera_id_names = [camera_id.logical_name for camera_id in rig.camera_ids] + + metadata = Metadata( + scene_id=scene_id, + version_string=version_string, + training_date=datetime.now().strftime("%Y-%m-%d"), + dataset_hash=str(uuid.uuid4()), + uuid=str(uuid.uuid4()), + is_resumable=False, + sensors=Metadata.Sensors(camera_ids=camera_id_names, lidar_ids=[]), + logger=Metadata.Logger(name=None, run_id=None, run_url=None), + time_range=Metadata.TimeRange(start=time_range_start, end=time_range_end), + ) + + # 11. Create the USDZ file + _create_usdz_file( + output_path, + metadata, + rig, + traffic_objects_dict, + scene_id, + scene, + dataset, + include_map, + ) + + # 12. Return the Artifact instance + return Artifact(source=output_path) + + +def _extract_camera_info_from_scene( + scene: Scene, + scene_id: str, +) -> tuple[list[CameraId], dict]: + """ + Extract camera information from scene.data_access_info['sensor_calibration']. + + Args: + scene: Scene object. + scene_id: Scene ID. + + Returns: + (camera_ids, camera_calibrations) tuple. + - camera_ids: list of CameraId objects. + - camera_calibrations: dict of camera calibration information, in the same format as artifact_2. + """ + camera_ids = [] + camera_calibrations = {} + + # Check whether sensor_calibration exists + if not hasattr(scene, 'data_access_info') or not scene.data_access_info: + logger.warning("scene.data_access_info does not exist, skipping camera info extraction") + return camera_ids, camera_calibrations + + sensor_calibration = scene.data_access_info.get('sensor_calibration') + if not sensor_calibration: + logger.warning("scene.data_access_info['sensor_calibration'] does not exist, skipping camera info extraction") + return camera_ids, camera_calibrations + + # Iterate over camera information in sensor_calibration. + # sensor_calibration is expected to be a dict whose keys are camera names and values are calibration info. + if not isinstance(sensor_calibration, dict): + logger.warning("sensor_calibration is not a dict, skipping camera info extraction") + return camera_ids, camera_calibrations + + unique_sensor_idx = 0 + for camera_name, calibration_info in sensor_calibration['cameras'].items(): + try: + # Build unique_camera_id (format: logical_sensor_name@sequence_id) + unique_camera_id = f"{camera_name}@{scene_id}" + + # Extract position and rotation information. + # Assume calibration_info contains position and rotation fields. + # rotation is a quaternion in the order [x, y, z, w]. + position = calibration_info.get('sensor2ego_translation', [0.0, 0.0, 0.0]) + rotation = calibration_info.get('sensor2ego_rotation', [0.0, 0.0, 0.0, 1.0]) # [x, y, z, w] + + # Ensure position and rotation are lists or arrays + if isinstance(position, (int, float)): + position = [float(position), 0.0, 0.0] + elif len(position) < 3: + position = list(position) + [0.0] * (3 - len(position)) + + if isinstance(rotation, (int, float)): + rotation = [0.0, 0.0, 0.0, 1.0] + elif len(rotation) < 4: + # If there are only 3 values, assume they are Euler angles and convert to a quaternion + if len(rotation) == 3: + r = R.from_euler('xyz', rotation) + rotation = r.as_quat() # [x, y, z, w] + else: + rotation = [0.0, 0.0, 0.0, 1.0] + + # Ensure rotation is in [x, y, z, w] format + if len(rotation) == 4: + qx, qy, qz, qw = rotation[0], rotation[1], rotation[2], rotation[3] + else: + logger.warning(f"Camera {camera_name} has invalid rotation format, using default value") + qx, qy, qz, qw = 0.0, 0.0, 0.0, 1.0 + + # Build the T_sensor_rig transform matrix (4x4). + # Build a rotation matrix from the quaternion. + r_quat = R.from_quat([qx, qy, qz, qw]) + rotation_matrix = r_quat.as_matrix() + + # Build the full transform matrix + T_sensor_rig = np.eye(4) + T_sensor_rig[:3, :3] = rotation_matrix + T_sensor_rig[:3, 3] = position[:3] + + # Create CameraId object + camera_id = CameraId( + logical_name=camera_name, + trajectory_idx=0, + sequence_id=scene_id, + unique_id=unique_camera_id, + ) + camera_ids.append(camera_id) + + # Build camera_calibration dict. + # Extract camera intrinsics if present. + camera_model = calibration_info.get('camera_model', {}) + if not camera_model: + # If no camera model is provided, fall back to default values + camera_model = { + "type": "pinhole", # Use pinhole model by default + "parameters": { + "resolution": calibration_info.get('resolution', [1920, 1080]), + "focal_length": calibration_info.get('focal_length', [1000.0, 1000.0]), + "principal_point": calibration_info.get('principal_point', [960.0, 540.0]), + } + } + + camera_calibrations[unique_camera_id] = { + "sequence_id": scene_id, + "logical_sensor_name": camera_name, + "unique_sensor_idx": unique_sensor_idx, + "T_sensor_rig": T_sensor_rig.tolist(), + "camera_model": camera_model, + } + + unique_sensor_idx += 1 + logger.info(f"Successfully extracted camera info: {camera_name} (unique_id: {unique_camera_id})") + + except Exception as e: + logger.warning(f"Failed to extract camera info for {camera_name}: {e}") + continue + + logger.info(f"Extracted {len(camera_ids)} cameras in total") + return camera_ids, camera_calibrations + + +def _extract_agent_trajectory( + scene: Scene, + scene_cache, + agent: AgentMetadata, + dt: float, + base_timestamp_us: Optional[int], +) -> tuple[Optional[Trajectory], Optional[VehicleConfig]]: + """ + Extract the full trajectory for an agent. + + Returns: + (Trajectory, VehicleConfig) or (None, None) if extraction fails. + """ + try: + timestamps_us = [] + poses_vec3 = [] + poses_quat = [] + + # Iterate over all timesteps + for ts in range(agent.first_timestep, agent.last_timestep + 1): + try: + state = scene_cache.get_raw_state(agent.name, ts) + + # Get position and heading + x = state.get_attr("x") if hasattr(state, 'get_attr') else state.x + y = state.get_attr("y") if hasattr(state, 'get_attr') else state.y + z = state.get_attr("z") if hasattr(state, 'get_attr') else (state.z if hasattr(state, 'z') else 0.0) + heading = state.get_attr("h") if hasattr(state, 'get_attr') else state.h + + # Convert to numpy arrays (handling scalar cases) + if isinstance(x, (int, float)): + x = np.array([x]) + if isinstance(y, (int, float)): + y = np.array([y]) + if isinstance(z, (int, float)): + z = np.array([z]) + if isinstance(heading, (int, float)): + heading = np.array([heading]) + + # Take the first element (if they are arrays) + x_val = float(x[0] if x.ndim > 0 else x) + y_val = float(y[0] if y.ndim > 0 else y) + z_val = float(z[0] if z.ndim > 0 else z) + heading_val = float(heading[0] if heading.ndim > 0 else heading) + + # Compute timestamp + if base_timestamp_us is None: + timestamp_us = int(ts * dt * 1e6) + else: + timestamp_us = int(base_timestamp_us + ts * dt * 1e6) + + timestamps_us.append(timestamp_us) + poses_vec3.append([x_val, y_val, z_val]) + + # Convert heading to quaternion. + # Heading is in radians, rotation about z-axis. + quat = R.from_euler('z', heading_val).as_quat() # [x, y, z, w] + poses_quat.append(quat) + + except Exception as e: + logger.debug(f"Failed to get state for agent {agent.name} at ts {ts}: {e}") + continue + + if len(timestamps_us) == 0: + return None, None + + # Create QVec + poses = QVec( + vec3=np.array(poses_vec3, dtype=np.float32), + quat=np.array(poses_quat, dtype=np.float32), + ) + + # Create Trajectory + trajectory = Trajectory( + timestamps_us=np.array(timestamps_us, dtype=np.uint64), + poses=poses, + ) + + # Create VehicleConfig (from extent) + vehicle_config = None + if hasattr(agent.extent, 'length'): + vehicle_config = VehicleConfig( + aabb_x_m=agent.extent.length, + aabb_y_m=agent.extent.width, + aabb_z_m=agent.extent.height, + aabb_x_offset_m=-agent.extent.length / 2, # Simplifying assumption + aabb_y_offset_m=0.0, + aabb_z_offset_m=-agent.extent.height / 2, + ) + + return trajectory, vehicle_config + + except Exception as e: + logger.error(f"Failed to extract trajectory for agent {agent.name}: {e}") + return None, None + + +def _transform_trajectory_to_local( + trajectory: Trajectory, + world_to_nre: np.ndarray, +) -> Trajectory: + """ + Transform a trajectory from the global coordinate frame into a local (NRE) frame. + + Args: + trajectory: Trajectory in the global coordinate frame. + world_to_nre: Transform matrix from global coordinates to NRE coordinates (4x4). + + Returns: + Trajectory in the local coordinate frame. + """ + # Extract translation component + translation = world_to_nre[:3, 3] + + # Transform positions (vec3) + local_positions = trajectory.poses.vec3 + translation + + # Keep quaternions unchanged (assume pure translation without rotation). + # If world_to_nre includes rotation, we would need to apply that to the quaternions. + # For now this is simplified to translation only. + local_quat = trajectory.poses.quat.copy() + + # Create a new QVec + local_poses = QVec( + vec3=local_positions, + quat=local_quat, + ) + + # Create a new Trajectory + return Trajectory( + timestamps_us=trajectory.timestamps_us.copy(), + poses=local_poses, + ) + + +def _write_map_to_usdz( + zip_file: zipfile.ZipFile, + scene: Scene, + dataset: UnifiedDataset, + logger: logging.Logger, +) -> None: + """ + Write map information into the USDZ file. + + Prefer to obtain a VectorMap from UnifiedDataset.map_api, then: + 1. Try to serialize the VectorMap to protobuf and store it (recommended). + 2. If that fails, try to locate the raw XODR file as a fallback. + + Note: artifact.py must support loading maps from protobuf, otherwise only XODR can be used. + """ + map_written = False + + # Method 1: directly get a VectorMap from UnifiedDataset and serialize it to protobuf + try: + if ( + hasattr(dataset, 'incl_vector_map') + and dataset.incl_vector_map + and hasattr(dataset, '_map_api') + and dataset._map_api + ): + if hasattr(scene, 'location') and scene.location: + map_name = f"{scene.env_name}:{scene.location}" + vector_map = dataset._map_api.get_map(map_name, **dataset.vector_map_params) + + if vector_map: + # Serialize VectorMap to protobuf + try: + import trajdata.proto.vectorized_map_pb2 as map_proto + vec_map_proto = vector_map.to_proto() + proto_bytes = vec_map_proto.SerializeToString() + + # Store as map.pb + zip_file.writestr("map.pb", proto_bytes) + logger.info(f"Successfully wrote VectorMap as protobuf (map.pb) for {map_name}") + map_written = True + except Exception as e: + logger.debug(f"Failed to serialize VectorMap to protobuf: {e}") + except Exception as e: + logger.debug(f"Could not get VectorMap from dataset API: {e}") + + # Method 2: if protobuf serialization fails, try to find the original XODR file (fallback) + if not map_written: + xodr_content = None + + # Try to find an XODR file in the raw data directories + try: + if hasattr(scene, 'location') and scene.location: + # nuplan XODR files are typically stored in data_dir.parent / "maps" / "{location}.xodr" + if hasattr(dataset, 'data_dirs') and dataset.data_dirs: + for env_name, data_dir in dataset.data_dirs.items(): + if env_name == scene.env_name: + # According to nuplan_dataset.py:381, map_root = data_dir.parent / "maps" + xodr_path = Path(data_dir).parent / "maps" / f"{scene.location}.xodr" + if xodr_path.exists(): + xodr_content = xodr_path.read_text(encoding='utf-8') + logger.info(f"Found XODR file at {xodr_path}") + break + except Exception as e: + logger.debug(f"Could not find XODR file in data directories: {e}") + + # If an XODR file is found, write it into the USDZ + if xodr_content: + zip_file.writestr("map.xodr", xodr_content.encode('utf-8')) + logger.info("Successfully wrote map.xodr to USDZ file") + map_written = True + + if not map_written: + logger.warning( + f"Could not write map for scene {scene.name} " + f"(location: {getattr(scene, 'location', 'unknown')}). " + f"Map will not be available in the USDZ file." + ) + + + + +def _is_static_object(trajectory: Trajectory, velocity_threshold: float = 0.1) -> bool: + """ + Determine whether an object is static (based on its velocity). + """ + if len(trajectory) < 2: + return True + + # Compute average velocity + positions = trajectory.poses.vec3 + timestamps = trajectory.timestamps_us.astype(np.float64) / 1e6 # convert to seconds + + velocities = [] + for i in range(1, len(positions)): + dt_sec = timestamps[i] - timestamps[i - 1] + if dt_sec > 0: + displacement = np.linalg.norm(positions[i] - positions[i - 1]) + velocity = displacement / dt_sec + velocities.append(velocity) + + if len(velocities) == 0: + return True + + avg_velocity = np.mean(velocities) + return avg_velocity < velocity_threshold + + +def _create_usdz_file( + output_path: str, + metadata: Metadata, + rig: Optional[Rig], + traffic_objects: TrafficObjects, + sequence_id: str, + scene: Scene, + dataset: UnifiedDataset, + include_map: bool, +) -> None: + """ + Create a USDZ file (technically a ZIP file). + """ + output_path = Path(output_path) + output_path.parent.mkdir(parents=True, exist_ok=True) + + with zipfile.ZipFile(output_path, 'w', zipfile.ZIP_DEFLATED) as zip_file: + # 1. Write metadata.yaml + metadata_dict = metadata.to_dict() + yaml_content = yaml.dump(metadata_dict, default_flow_style=False) + zip_file.writestr("metadata.yaml", yaml_content) + + # 2. Write rig_trajectories.json + if rig: + # Get camera calibrations if present + camera_calibrations = getattr(rig, '_camera_calibrations', {}) + + # Build the cameras_frame_timestamps_us dictionary + cameras_frame_timestamps_us = {} + if rig.camera_ids: + # Use the rig trajectory timestamps for each camera + rig_timestamps = rig.trajectory.timestamps_us.tolist() + for camera_id in rig.camera_ids: + cameras_frame_timestamps_us[camera_id.unique_id] = rig_timestamps + + rig_data = { + "world_to_nre": { + "matrix": rig.world_to_nre.tolist() + }, + "camera_calibrations": camera_calibrations, + "rig_trajectories": [ + { + "sequence_id": rig.sequence_id, + "T_rig_world_timestamps_us": rig.trajectory.timestamps_us.tolist(), + "T_rig_worlds": [pose.as_se3().tolist() for pose in rig.trajectory.poses], + "cameras_frame_timestamps_us": cameras_frame_timestamps_us, + "rig_bbox": None, # can be added later + } + ], + "T_world_base": np.eye(4).tolist(), # identity by default + } + + # If there is a vehicle_config, add rig_bbox + if rig.vehicle_config: + rig_data["rig_trajectories"][0]["rig_bbox"] = { + "centroid": [ + rig.vehicle_config.aabb_x_offset_m + rig.vehicle_config.aabb_x_m / 2, + rig.vehicle_config.aabb_y_offset_m, + rig.vehicle_config.aabb_z_offset_m + rig.vehicle_config.aabb_z_m / 2, + ], + "dim": [ + rig.vehicle_config.aabb_x_m, + rig.vehicle_config.aabb_y_m, + rig.vehicle_config.aabb_z_m, + ], + "rot": [0.0, 0.0, 0.0], + } + + zip_file.writestr("rig_trajectories.json", json.dumps(rig_data, indent=2)) + + # 3. Write sequence_tracks.json + tracks_data = { + "tracks_id": [], + "tracks_label_class": [], + "tracks_flags": [], + "tracks_timestamps_us": [], + "tracks_poses": [], + } + cuboids_dims = [] + + for track_id, traffic_obj in traffic_objects.items(): + tracks_data["tracks_id"].append(track_id) + tracks_data["tracks_label_class"].append(traffic_obj.label_class) + tracks_data["tracks_flags"].append("CONTROLLABLE" if not traffic_obj.is_static else "STATIC") + tracks_data["tracks_timestamps_us"].append(traffic_obj.trajectory.timestamps_us.tolist()) + + # Convert QVec to [x, y, z, qx, qy, qz, qw] format + poses_list = [] + for pose in traffic_obj.trajectory.poses: + pose_array = np.concatenate([pose.vec3, pose.quat]) + poses_list.append(pose_array.tolist()) + tracks_data["tracks_poses"].append(poses_list) + + cuboids_dims.append([traffic_obj.aabb.x, traffic_obj.aabb.y, traffic_obj.aabb.z]) + + sequence_tracks_data = { + sequence_id: { + "tracks_data": tracks_data, + "cuboidtracks_data": { + "cuboids_dims": cuboids_dims, + }, + } + } + + zip_file.writestr("sequence_tracks.json", json.dumps(sequence_tracks_data, indent=2)) + + # 4. Write map if present + if include_map: + _write_map_to_usdz(zip_file, scene, dataset, logger) + + logger.info(f"Created USDZ file: {output_path}") + + +if __name__ == "__main__": + + # artifact_2 = Artifact(source='data/nre-artifacts/all-usdzs/sample_set/25.07_release/Batch0001/05bb8212-63e1-40a8-b4fc-3142c0e94646/05bb8212-63e1-40a8-b4fc-3142c0e94646.usdz') + + dataset = UnifiedDataset( + desired_data=["nuplan_train"], + cache_location="/inspire/hdd/project/roboticsystem2/wangcaojun-240208020180/repo-wcj/trajdata/datasets", + incl_vector_map=True, + rebuild_cache=False, + rebuild_maps=False, + require_map_cache=False, + num_workers=1, + desired_dt=0.5, + verbose=True, + data_dirs={ # Remember to change this to match your filesystem! + "nuplan_train": "/inspire/hdd/project/roboticsystem2/public/nuplan/dataset/nuplan-v1.1", + }, + ) + + # artifact = convert_unified_dataset_to_artifact( + # dataset=dataset, + # scene_idx=0, + # output_path="output/nuplan_train_1aa44d46e4ab5bc7.usdz", + # scene_id="nuplan_train_1aa44d46e4ab5bc7", + # ) + + artifact = Artifact(source='output/nuplan_train_1aa44d46e4ab5bc7.usdz') + artifact_2 = Artifact(source='data/nre-artifacts/all-usdzs/sample_set/25.07_release/Batch0001/05bb8212-63e1-40a8-b4fc-3142c0e94646/05bb8212-63e1-40a8-b4fc-3142c0e94646.usdz') + + print("✓ Successfully loaded reference artifact") + + # Compare the two artifacts + if artifact is None: + print("\n" + "=" * 80) + print("⚠ Unable to compare: converted artifact does not exist") + print("=" * 80) + print("\nShowing information for the reference artifact only:") + print(f" Scene ID: {artifact_2.scene_id}") + print(f" Rig trajectory length: {len(artifact_2.rig.trajectory)}") + print(f" Traffic objects: {len(artifact_2.traffic_objects)}") + print(f" World to NRE matrix:\n{artifact_2.rig.world_to_nre}") + print(f" First pose position: {artifact_2.rig.trajectory.poses[0].vec3}") + exit(0) + + print("=" * 80) + print("Artifact comparison analysis") + print("=" * 80) + + print("\n[Basic information]") + print("Artifact 1 (converted):") + print(f" Scene ID: {artifact.scene_id}") + print(f" Rig trajectory length: {len(artifact.rig.trajectory)}") + print(f" Traffic objects: {len(artifact.traffic_objects)}") + + print("\nArtifact 2 (reference case):") + print(f" Scene ID: {artifact_2.scene_id}") + print(f" Rig trajectory length: {len(artifact_2.rig.trajectory)}") + print(f" Traffic objects: {len(artifact_2.traffic_objects)}") + + print("\n[Rig trajectory analysis]") + print("\nArtifact 1 Rig:") + rig1 = artifact.rig + print(f" Sequence ID: {rig1.sequence_id}") + print(f" World to NRE matrix shape: {rig1.world_to_nre.shape}") + print(f" World to NRE matrix:\n{rig1.world_to_nre}") + print(f" Trajectory timestamps range: {rig1.trajectory.timestamps_us[0]} - {rig1.trajectory.timestamps_us[-1]}") + print(f" First pose position (vec3): {rig1.trajectory.poses[0].vec3}") + print(f" First pose quaternion: {rig1.trajectory.poses[0].quat}") + print(f" Last pose position (vec3): {rig1.trajectory.poses[-1].vec3}") + print(f" Last pose quaternion: {rig1.trajectory.poses[-1].quat}") + + print("\nArtifact 2 Rig:") + rig2 = artifact_2.rig + print(f" Sequence ID: {rig2.sequence_id}") + print(f" World to NRE matrix shape: {rig2.world_to_nre.shape}") + print(f" World to NRE matrix:\n{rig2.world_to_nre}") + print(f" Trajectory timestamps range: {rig2.trajectory.timestamps_us[0]} - {rig2.trajectory.timestamps_us[-1]}") + print(f" First pose position (vec3): {rig2.trajectory.poses[0].vec3}") + print(f" First pose quaternion: {rig2.trajectory.poses[0].quat}") + print(f" Last pose position (vec3): {rig2.trajectory.poses[-1].vec3}") + print(f" Last pose quaternion: {rig2.trajectory.poses[-1].quat}") + + print("\n[Coordinate frame differences]") + print("\nArtifact 1:") + print(f" World to NRE is identity: {np.allclose(rig1.world_to_nre, np.eye(4))}") + print(" Trajectory position ranges:") + positions1 = rig1.trajectory.poses.vec3 + print(f" X: [{positions1[:, 0].min():.2f}, {positions1[:, 0].max():.2f}]") + print(f" Y: [{positions1[:, 1].min():.2f}, {positions1[:, 1].max():.2f}]") + print(f" Z: [{positions1[:, 2].min():.2f}, {positions1[:, 2].max():.2f}]") + + print("\nArtifact 2:") + print(f" World to NRE is identity: {np.allclose(rig2.world_to_nre, np.eye(4))}") + print(" Trajectory position ranges:") + positions2 = rig2.trajectory.poses.vec3 + print(f" X: [{positions2[:, 0].min():.2f}, {positions2[:, 0].max():.2f}]") + print(f" Y: [{positions2[:, 1].min():.2f}, {positions2[:, 1].max():.2f}]") + print(f" Z: [{positions2[:, 2].min():.2f}, {positions2[:, 2].max():.2f}]") + + print("\n[Traffic object trajectory analysis]") + if len(artifact.traffic_objects) > 0: + sample_obj1 = list(artifact.traffic_objects.values())[0] + print("\nArtifact 1 first traffic object:") + print(f" Track ID: {sample_obj1.track_id}") + print(f" Trajectory length: {len(sample_obj1.trajectory)}") + print(f" First pose position: {sample_obj1.trajectory.poses[0].vec3}") + print(f" Last pose position: {sample_obj1.trajectory.poses[-1].vec3}") + + if len(artifact_2.traffic_objects) > 0: + sample_obj2 = list(artifact_2.traffic_objects.values())[0] + print("\nArtifact 2 first traffic object:") + print(f" Track ID: {sample_obj2.track_id}") + print(f" Trajectory length: {len(sample_obj2.trajectory)}") + print(f" First pose position: {sample_obj2.trajectory.poses[0].vec3}") + print(f" Last pose position: {sample_obj2.trajectory.poses[-1].vec3}") + + print("\n" + "=" * 80) \ No newline at end of file diff --git a/src/utils/alpasim_utils/trajdata_data_source.py b/src/utils/alpasim_utils/trajdata_data_source.py new file mode 100644 index 00000000..e6962a6b --- /dev/null +++ b/src/utils/alpasim_utils/trajdata_data_source.py @@ -0,0 +1,1129 @@ +# SPDX-License-Identifier: Apache-2.0 +# Copyright (c) 2025 NVIDIA Corporation + +""" +TrajdataDataSource: Implementation for loading scene data directly from trajdata + +This class demonstrates how to create a SceneDataSource implementation that loads +data directly from trajdata converted data without requiring USDZ format. This is +useful for researchers using trajdata datasets. + +Usage example: + from trajdata import UnifiedDataset + from alpasim_utils.trajdata_data_source import TrajdataDataSource + + # Load trajdata dataset + dataset = UnifiedDataset( + desired_data=["nusc_mini"], + data_dirs={"/path/to/trajdata/data"}, + ... + ) + + # Get a scene + scene = dataset.get_scene("nusc_mini", "scene-0001") + + # Create data source + data_source = TrajdataDataSource.from_trajdata_scene(scene) + + # Now can be used in Runtime + # artifacts = {data_source.scene_id: data_source} +""" + +from __future__ import annotations + +import copy +import logging +import os +import threading +import time +from dataclasses import dataclass +from typing import Optional + +import numpy as np +from scipy.spatial.transform import Rotation as R +logger = logging.getLogger(__name__) + +try: + from trajdata.caching import EnvCache + from trajdata.data_structures.agent import AgentMetadata + from trajdata.data_structures.scene_metadata import Scene + from trajdata.dataset import UnifiedDataset + from trajdata.maps import VectorMap + + # Try to import AgentBatch (may not exist in all versions) + try: + from trajdata import AgentBatch + except ImportError: + AgentBatch = None +except ImportError as e: + AgentBatch = None + Scene = None + UnifiedDataset = None + EnvCache = None + AgentMetadata = None + VectorMap = None + # Only log warning at debug level to avoid noise if trajdata is intentionally not installed + logger.debug(f"trajdata not available: {e}. TrajdataDataSource will not work.") + +from alpasim_utils.artifact import Metadata +from alpasim_utils.qvec import QVec +from alpasim_utils.scenario import AABB, CameraId, Rig, TrafficObject, TrafficObjects, VehicleConfig +from alpasim_utils.scene_data_source import SceneDataSource +from alpasim_utils.trajectory import Trajectory + + + + +@dataclass +class TrajdataDataSource(SceneDataSource): + """ + Implementation for loading scene data directly from trajdata. + + This class implements the SceneDataSource protocol, allowing direct loading + from trajdata Scene or AgentBatch objects without requiring USDZ format. + """ + + _scene: Scene | None = None + _scene_cache: EnvCache | None = None + _dataset: UnifiedDataset | None = None + _rig: Rig | None = None + _traffic_objects: TrafficObjects | None = None + _map: VectorMap | None = None + _metadata: Metadata | None = None + _smooth_trajectories: bool = True + _scene_id: str = "" + + @classmethod + def from_trajdata_scene( + cls, + scene: Scene, + dataset: Optional[UnifiedDataset] = None, + scene_cache: Optional[EnvCache] = None, + scene_id: Optional[str] = None, + smooth_trajectories: bool = True, + base_timestamp_us: int = 0, + ) -> TrajdataDataSource: + """ + Create TrajdataDataSource from trajdata Scene object. + + Args: + scene: trajdata Scene object + dataset: UnifiedDataset instance (for getting scene_cache and map) + scene_cache: Optional EnvCache instance (if not provided, will be created from dataset) + scene_id: Optional scene ID (if not provided, uses scene.name) + smooth_trajectories: Whether to smooth trajectories + base_timestamp_us: Base timestamp in microseconds, starts from 0 if None + + Returns: + TrajdataDataSource instance + """ + if Scene is None: + raise ImportError("trajdata is not installed. Please install it to use TrajdataDataSource.") + + data_source = cls( + _scene=scene, + _dataset=dataset, + _scene_cache=scene_cache, + _scene_id=scene_id or scene.name, + _smooth_trajectories=smooth_trajectories, + ) + data_source._base_timestamp_us = base_timestamp_us + return data_source + + @classmethod + def from_agent_batch( + cls, + batch: AgentBatch, + scene_id: str, + smooth_trajectories: bool = True, + ) -> TrajdataDataSource: + """ + Create TrajdataDataSource from trajdata AgentBatch object. + + Note: This method requires the batch to contain complete scene information. + It is generally recommended to use from_trajdata_scene instead. + + Args: + batch: trajdata AgentBatch object + scene_id: Scene ID + smooth_trajectories: Whether to smooth trajectories + + Returns: + TrajdataDataSource instance + """ + if AgentBatch is None: + raise ImportError("trajdata is not installed. Please install it to use TrajdataDataSource.") + + data_source = cls(scene_id=scene_id) + data_source._smooth_trajectories = smooth_trajectories + # Extract data from batch + data_source._load_from_batch(batch) + return data_source + + def _load_from_batch(self, batch: AgentBatch) -> None: + """Load data from AgentBatch (internal method)""" + # Need to extract data based on batch structure + # Specific implementation depends on your trajdata data format + raise NotImplementedError( + "from_agent_batch needs to be implemented based on your trajdata data format. " + "It is recommended to use from_trajdata_scene method instead." + ) + + @property + def scene_id(self) -> str: + """Scene ID""" + if self._scene_id: + return self._scene_id + if self._scene is not None: + return self._scene.name + raise ValueError("scene_id is not set and cannot be obtained from scene") + + @scene_id.setter + def scene_id(self, value: str) -> None: + self._scene_id = value + + def _get_scene_cache(self) -> EnvCache: + """Get or create scene_cache""" + if self._scene_cache is not None: + return self._scene_cache + + if self._scene is None: + raise ValueError("Cannot create scene_cache: scene is not set") + + if self._dataset is None: + raise ValueError("Cannot create scene_cache: dataset is not set") + + # Create SceneCache + self._scene_cache = self._dataset.cache_class( + self._dataset.cache_path, self._scene, self._dataset.augmentations + ) + self._scene_cache.set_obs_format(self._dataset.obs_format) + return self._scene_cache + + def _extract_agent_trajectory( + self, + agent: AgentMetadata, + ) -> tuple[Optional[Trajectory], Optional[VehicleConfig]]: + """Extract complete trajectory for agent (refer to trajdata_artifact_converter.py implementation)""" + if self._scene is None: + return None, None + + scene_cache = self._get_scene_cache() + dt = self._scene.dt + base_timestamp_us = getattr(self, "_base_timestamp_us", None) + + try: + timestamps_us = [] + poses_vec3 = [] + poses_quat = [] + + # Iterate through all timesteps + for ts in range(agent.first_timestep, agent.last_timestep + 1): + try: + state = scene_cache.get_raw_state(agent.name, ts) + + # Get position and orientation + x = state.get_attr("x") if hasattr(state, 'get_attr') else state.x + y = state.get_attr("y") if hasattr(state, 'get_attr') else state.y + z = state.get_attr("z") if hasattr(state, 'get_attr') else (state.z if hasattr(state, 'z') else 0.0) + heading = state.get_attr("h") if hasattr(state, 'get_attr') else state.h + + # Convert to numpy array (handle scalar case) + if isinstance(x, (int, float)): + x = np.array([x]) + if isinstance(y, (int, float)): + y = np.array([y]) + if isinstance(z, (int, float)): + z = np.array([z]) + if isinstance(heading, (int, float)): + heading = np.array([heading]) + + # Take first element (if array) + x_val = float(x[0] if x.ndim > 0 else x) + y_val = float(y[0] if y.ndim > 0 else y) + z_val = float(z[0] if z.ndim > 0 else z) + heading_val = float(heading[0] if heading.ndim > 0 else heading) + + # Calculate timestamp + if base_timestamp_us is None: + timestamp_us = int(ts * dt * 1e6) + else: + timestamp_us = int(base_timestamp_us + ts * dt * 1e6) + + timestamps_us.append(timestamp_us) + poses_vec3.append([x_val, y_val, z_val]) + + # Convert heading to quaternion + quat = R.from_euler('z', heading_val).as_quat() # [x, y, z, w] + poses_quat.append(quat) + + except Exception as e: + logger.debug(f"Failed to get state for agent {agent.name} at ts {ts}: {e}") + continue + + if len(timestamps_us) == 0: + return None, None + + # Create QVec + poses = QVec( + vec3=np.array(poses_vec3, dtype=np.float64), + quat=np.array(poses_quat, dtype=np.float64), + ) + + # Create Trajectory + trajectory = Trajectory( + timestamps_us=np.array(timestamps_us, dtype=np.uint64), + poses=poses, + ) + + # Create VehicleConfig (extract from extent) + vehicle_config = None + if hasattr(agent.extent, 'length'): + vehicle_config = VehicleConfig( + aabb_x_m=agent.extent.length, + aabb_y_m=agent.extent.width, + aabb_z_m=agent.extent.height, + aabb_x_offset_m=-agent.extent.length / 2, + aabb_y_offset_m=0.0, + aabb_z_offset_m=-agent.extent.height / 2, + ) + + return trajectory, vehicle_config + + except Exception as e: + logger.error(f"Failed to extract trajectory for agent {agent.name}: {e}") + return None, None + + @property + def rig(self) -> Rig: + """Load and return Rig object for ego vehicle""" + if self._rig is not None: + return self._rig + + if self._scene is None: + raise ValueError("Cannot load rig: scene is not set") + + # Get all agents + all_agents = self._scene.agents if self._scene.agents else [] + + # Identify ego agent + ego_agent = next((a for a in all_agents if a.name == "ego"), None) + if ego_agent is None and len(all_agents) > 0: + # If no ego, use first agent + ego_agent = all_agents[0] + logger.warning(f"No ego agent found, using first agent: {ego_agent.name}") + + if ego_agent is None: + raise ValueError("No ego agent found in scene") + + # Extract ego trajectory + ego_trajectory, ego_vehicle_config = self._extract_agent_trajectory(ego_agent) + + if ego_trajectory is None: + raise ValueError("Cannot extract ego trajectory") + + # Calculate world_to_nre transformation matrix (use first trajectory point as origin) + world_to_nre = np.eye(4) + if len(ego_trajectory) > 0: + first_pose_position = ego_trajectory.poses[0].vec3 + world_to_nre[:3, 3] = -first_pose_position + logger.info( + f"Setting world_to_nre origin at first pose: {first_pose_position}, " + f"translation: {world_to_nre[:3, 3]}" + ) + + # Convert ego trajectory to local coordinates (NRE) + if len(ego_trajectory) > 0: + translation = world_to_nre[:3, 3] + local_positions = ego_trajectory.poses.vec3 + translation + + # Validate transform + first_pose_local = local_positions[0] + if np.linalg.norm(first_pose_local[:2]) > 1.0: + logger.warning( + f"First pose after transformation is not at origin: {first_pose_local}. " + f"Expected [0, 0, ~z], got {first_pose_local}" + ) + + local_quat = ego_trajectory.poses.quat.copy() + local_poses = QVec(vec3=local_positions, quat=local_quat) + ego_trajectory = Trajectory( + timestamps_us=ego_trajectory.timestamps_us.copy(), + poses=local_poses, + ) + + logger.info( + f"Transformed ego trajectory to local coordinates. " + f"First pose: {ego_trajectory.poses[0].vec3}, " + f"Range: X[{local_positions[:, 0].min():.2f}, {local_positions[:, 0].max():.2f}], " + f"Y[{local_positions[:, 1].min():.2f}, {local_positions[:, 1].max():.2f}], " + f"Z[{local_positions[:, 2].min():.2f}, {local_positions[:, 2].max():.2f}]" + ) + + # Extract camera information (refer to trajdata_artifact_converter.py) + camera_ids, _ = self._extract_camera_info_from_scene() + + self._rig = Rig( + sequence_id=self.scene_id, + trajectory=ego_trajectory, + camera_ids=camera_ids, + world_to_nre=world_to_nre, + vehicle_config=ego_vehicle_config, + ) + + return self._rig + + def _extract_camera_info_from_scene(self) -> tuple[list[CameraId], dict]: + """Extract camera information from scene (refer to trajdata_artifact_converter.py)""" + camera_ids = [] + camera_calibrations = {} + + if self._scene is None: + return camera_ids, camera_calibrations + + # Check if sensor_calibration information exists + if not hasattr(self._scene, 'data_access_info') or not self._scene.data_access_info: + logger.warning(f"scene.data_access_info does not exist, skipping camera information extraction") + return camera_ids, camera_calibrations + + sensor_calibration = self._scene.data_access_info.get('sensor_calibration') + if not sensor_calibration or not isinstance(sensor_calibration, dict): + logger.warning(f"sensor_calibration does not exist or has incorrect format, skipping camera information extraction") + return camera_ids, camera_calibrations + + unique_sensor_idx = 0 + for camera_name, calibration_info in sensor_calibration.get('cameras', {}).items(): + try: + unique_camera_id = f"{camera_name}@{self.scene_id}" + + position = calibration_info.get('sensor2ego_translation', [0.0, 0.0, 0.0]) + rotation = calibration_info.get('sensor2ego_rotation', [0.0, 0.0, 0.0, 1.0]) + + if isinstance(position, (int, float)): + position = [float(position), 0.0, 0.0] + elif len(position) < 3: + position = list(position) + [0.0] * (3 - len(position)) + + if isinstance(rotation, (int, float)): + rotation = [0.0, 0.0, 0.0, 1.0] + elif len(rotation) < 4: + if len(rotation) == 3: + r = R.from_euler('xyz', rotation) + rotation = r.as_quat() + else: + rotation = [0.0, 0.0, 0.0, 1.0] + + if len(rotation) == 4: + qx, qy, qz, qw = rotation[0], rotation[1], rotation[2], rotation[3] + else: + qx, qy, qz, qw = 0.0, 0.0, 0.0, 1.0 + + camera_id = CameraId( + logical_name=camera_name, + trajectory_idx=0, + sequence_id=self.scene_id, + unique_id=unique_camera_id, + ) + camera_ids.append(camera_id) + unique_sensor_idx += 1 + + except Exception as e: + logger.warning(f"Error extracting camera {camera_name} information: {e}") + continue + + if len(camera_ids) == 0: + # If no camera information, create a default one + logger.warning(f"Scene {self.scene_id} has no camera information, using default camera") + camera_ids.append( + CameraId( + logical_name="camera_front", + trajectory_idx=0, + sequence_id=self.scene_id, + unique_id="0@camera_front", + ) + ) + + return camera_ids, camera_calibrations + + def _is_static_object(self, trajectory: Trajectory, velocity_threshold: float = 0.1) -> bool: + """Determine if object is static (based on velocity)""" + if len(trajectory) < 2: + return True + + positions = trajectory.poses.vec3 + timestamps = trajectory.timestamps_us.astype(np.float64) / 1e6 + + velocities = [] + for i in range(1, len(positions)): + dt_sec = timestamps[i] - timestamps[i - 1] + if dt_sec > 0: + displacement = np.linalg.norm(positions[i] - positions[i - 1]) + velocity = displacement / dt_sec + velocities.append(velocity) + + if len(velocities) == 0: + return True + + avg_velocity = np.mean(velocities) + return avg_velocity < velocity_threshold + + @property + def traffic_objects(self) -> TrafficObjects: + """Load and return traffic objects""" + if self._traffic_objects is not None: + return self._traffic_objects + + if self._scene is None: + raise ValueError("Cannot load traffic_objects: scene is not set") + + # Get all agents + all_agents = self._scene.agents if self._scene.agents else [] + + # Identify ego agent + ego_agent = next((a for a in all_agents if a.name == "ego"), None) + if ego_agent is None and len(all_agents) > 0: + ego_agent = all_agents[0] + + traffic_dict = {} + for agent in all_agents: + # Skip ego agent + if agent.name == "ego" or agent == ego_agent: + continue + + # Extract trajectory + trajectory, _ = self._extract_agent_trajectory(agent) + + # Filter out empty trajectories or trajectories with only 1 data point + if trajectory is None or len(trajectory) < 2: + continue + + # Convert trajectory to local coordinates (NRE) - use rig's world_to_nre + if self._rig is None: + # If rig is not loaded yet, load it first + _ = self.rig + + world_to_nre = self._rig.world_to_nre + translation = world_to_nre[:3, 3] + local_positions = trajectory.poses.vec3 + translation + local_quat = trajectory.poses.quat.copy() + local_poses = QVec(vec3=local_positions, quat=local_quat) + trajectory = Trajectory( + timestamps_us=trajectory.timestamps_us.copy(), + poses=local_poses, + ) + + # Smooth if needed + if self._smooth_trajectories: + try: + import csaps + + css = csaps.CubicSmoothingSpline( + trajectory.timestamps_us / 1e6, + trajectory.poses.vec3.T, + normalizedsmooth=True, + ) + filtered_positions = css(trajectory.timestamps_us / 1e6).T + max_error = np.max(np.abs(filtered_positions - trajectory.poses.vec3)) + if max_error > 1.0: + logger.warning( + f"Max error in cubic spline approximation: {max_error:.6f} m for {agent.name=}" + ) + trajectory.poses.vec3 = filtered_positions + except ImportError: + logger.warning("csaps not installed, skipping trajectory smoothing") + + # Get AABB + if hasattr(agent.extent, 'length'): + aabb = AABB(x=agent.extent.length, y=agent.extent.width, z=agent.extent.height) + else: + # Default AABB + aabb = AABB(x=4.5, y=1.8, z=1.5) + + # Determine if static object + is_static = self._is_static_object(trajectory) + + # Get category label + label_class = agent.type.name if hasattr(agent.type, 'name') else "UNKNOWN" + + traffic_dict[agent.name] = TrafficObject( + track_id=agent.name, + aabb=aabb, + trajectory=trajectory, + is_static=is_static, + label_class=label_class, + ) + + self._traffic_objects = TrafficObjects(**traffic_dict) + return self._traffic_objects + + @property + def map(self) -> Optional[VectorMap]: + """Load and return VectorMap (obtained from dataset._map_api)""" + if self._map is not None: + return self._map + + if VectorMap is None: + logger.warning("trajdata is not installed, cannot load map") + return None + + if self._scene is None: + logger.warning("Cannot load map: scene is not set") + return None + + if self._dataset is None: + logger.warning("Cannot load map: dataset is not set") + return None + + # Get map from dataset._map_api (refer to trajdata_artifact_converter.py) + try: + # Check if dataset includes map support + if ( + not hasattr(self._dataset, 'incl_vector_map') + or not self._dataset.incl_vector_map + or not hasattr(self._dataset, '_map_api') + or self._dataset._map_api is None + ): + logger.debug(f"Dataset does not have map support enabled or map_api is unavailable") + return None + + # Build map name: "{env_name}:{location}" + if not hasattr(self._scene, 'location') or not self._scene.location: + logger.debug(f"Scene {self.scene_id} has no location information, cannot load map") + return None + + map_name = f"{self._scene.env_name}:{self._scene.location}" + + # Get vector_map_params (if exists) + vector_map_params = {} + if hasattr(self._dataset, 'vector_map_params'): + vector_map_params = self._dataset.vector_map_params + + # Get map from map_api + vec_map = self._dataset._map_api.get_map(map_name, **vector_map_params) + + if vec_map is None: + logger.debug(f"Scene {self.scene_id} (map_name: {map_name}) has no map data") + return None + + # Create an independent copy of VectorMap for current scene to avoid modifying + # map objects in shared cache. This allows continued use of MapAPI's disk cache + # and index loading capabilities while preventing coordinate system pollution + # between multiple scenes through shared VectorMap instances. + self._map = copy.deepcopy(vec_map) + + # Important: Transform map to local coordinate system (NRE) + # Since trajectories are already converted to local coordinates, map also needs + # to be converted to match. This is consistent with USDZ format handling: + # both map and trajectories need to be converted to the same coordinate system + if self._rig is None: + # If rig is not loaded yet, load it first (this will set world_to_nre) + _ = self.rig + + world_to_nre = self._rig.world_to_nre + + # Check if world_to_nre contains rotation + rotation_matrix = world_to_nre[:3, :3] + translation = world_to_nre[:3, 3] + has_rotation = not np.allclose(rotation_matrix, np.eye(3)) + + if has_rotation: + logger.warning( + f"world_to_nre contains rotation. Map transformation may need rotation handling. " + f"Currently only applying translation." + ) + + # Transform all points in map (center.points, left_boundary.points, right_boundary.points, etc.) + # Note: Must transform before finalize, as finalize may rebuild certain data structures + # Important: Only transform X, Y coordinates, align Z coordinate to trajectory Z baseline + # Because map Z usually represents height relative to ground (usually 0), while trajectory Z + # represents altitude. After transformation, map Z should align with trajectory Z + # (both relative to first trajectory point's Z, usually 0 after transformation) + translation_xy = translation[:2] # Only use X, Y translation + + # Get Z coordinate of first trajectory point (transformed baseline, usually 0) + first_traj_z = self.rig.trajectory.poses[0].vec3[2] if len(self.rig.trajectory) > 0 else 0.0 + + logger.info( + f"Map coordinate transformation: " + f"translation_xy={translation_xy}, " + f"first_traj_z={first_traj_z:.2f}m, " + f"map Z will be aligned to trajectory Z baseline" + ) + + def transform_map_points(points: np.ndarray) -> np.ndarray: + """Transform map points: only transform X, Y, align Z to trajectory Z baseline""" + if points is None or len(points) == 0 or points.ndim != 2 or points.shape[1] < 3: + return points + + points_copy = points.copy() + + # Transform X, Y coordinates + if has_rotation: + # If rotation exists, need to rotate X, Y + xy_rotated = (points_copy[:, :2] @ rotation_matrix[:2, :2].T) + translation_xy + points_copy[:, 0] = xy_rotated[:, 0] + points_copy[:, 1] = xy_rotated[:, 1] + else: + # Only translate X, Y + points_copy[:, 0] = points_copy[:, 0] + translation_xy[0] + points_copy[:, 1] = points_copy[:, 1] + translation_xy[1] + + # Z coordinate alignment: align map Z to trajectory Z baseline + # Map Z is usually height relative to ground (usually 0), + # after transformation should align with trajectory Z (both relative to first + # trajectory point's Z, usually 0 after transformation) + # So: new_z = original_z + first_traj_z + # If map Z=0 (ground), after transformation it becomes first_traj_z (usually 0) + points_copy[:, 2] = points_copy[:, 2] + first_traj_z + + return points_copy + + if hasattr(self._map, "lanes"): + for lane_idx, lane in enumerate(self._map.lanes): + # Transform center.points + if hasattr(lane, "center") and hasattr(lane.center, "points"): + points = lane.center.points + if points is not None and len(points) > 0: + try: + transformed_points = transform_map_points(points) + lane.center.points = transformed_points + except Exception as e: + logger.warning(f"Failed to transform lane {lane_idx} center.points: {e}") + + # Transform left_boundary.points + if hasattr(lane, "left_boundary") and hasattr(lane.left_boundary, "points"): + points = lane.left_boundary.points + if points is not None and len(points) > 0: + try: + transformed_points = transform_map_points(points) + lane.left_boundary.points = transformed_points + except Exception as e: + logger.warning(f"Failed to transform lane {lane_idx} left_boundary.points: {e}") + + # Transform right_boundary.points + if hasattr(lane, "right_boundary") and hasattr(lane.right_boundary, "points"): + points = lane.right_boundary.points + if points is not None and len(points) > 0: + try: + transformed_points = transform_map_points(points) + lane.right_boundary.points = transformed_points + except Exception as e: + logger.warning(f"Failed to transform lane {lane_idx} right_boundary.points: {e}") + + # Transform other possible point attributes (if any) + for attr_name in ['intersections', 'crosswalks', 'stop_lines']: + if hasattr(lane, attr_name): + attr_value = getattr(lane, attr_name) + if isinstance(attr_value, list): + for item in attr_value: + if hasattr(item, 'points'): + points = item.points + if points is not None and len(points) > 0: + try: + transformed_points = transform_map_points(points) + item.points = transformed_points + except Exception as e: + logger.debug(f"Failed to transform {attr_name} points: {e}") + + # If map needs finalize, call it (after transformation) + # Note: finalize may rebuild certain indices but won't change point coordinates + # But for safety, we verify transformation again after finalize + if hasattr(self._map, "__post_init__"): + self._map.__post_init__() + if hasattr(self._map, "compute_search_indices"): + self._map.compute_search_indices() + + # Verify again: check if first point's coordinates are still correct after finalize + if hasattr(self._map, "lanes") and len(self._map.lanes) > 0: + first_lane = self._map.lanes[0] + if hasattr(first_lane, "center") and hasattr(first_lane.center, "points"): + first_map_point_after_finalize = first_lane.center.points[0, :3] if len(first_lane.center.points) > 0 else None + if first_map_point_after_finalize is not None: + # Check if Z coordinate aligns with trajectory (should both be first_traj_z, usually 0) + actual_z = first_map_point_after_finalize[2] + if abs(actual_z - first_traj_z) > 1.0: # Allow 1 meter error + logger.warning( + f"Map Z coordinate may have been reset after finalize. " + f"Expected Z≈{first_traj_z:.2f}m (aligned to trajectory Z baseline), " + f"got Z={actual_z:.2f}m. " + f"This may cause coordinate misalignment." + ) + # If alignment is correct, no need to log (reduce noise) + + # Fix data types (if needed) + if hasattr(self._map, "lanes"): + for lane in self._map.lanes: + if hasattr(lane, "next_lanes") and isinstance(lane.next_lanes, list): + lane.next_lanes = set(lane.next_lanes) + if hasattr(lane, "prev_lanes") and isinstance(lane.prev_lanes, list): + lane.prev_lanes = set(lane.prev_lanes) + if hasattr(lane, "adj_lanes_right") and isinstance( + lane.adj_lanes_right, list + ): + lane.adj_lanes_right = set(lane.adj_lanes_right) + if hasattr(lane, "adj_lanes_left") and isinstance( + lane.adj_lanes_left, list + ): + lane.adj_lanes_left = set(lane.adj_lanes_left) + + # Verify map transformation: check if first lane's first point is within reasonable range + if hasattr(self._map, "lanes") and len(self._map.lanes) > 0: + first_lane = self._map.lanes[0] + if hasattr(first_lane, "center") and hasattr(first_lane.center, "points"): + first_map_point = first_lane.center.points[0, :3] if len(first_lane.center.points) > 0 else None + if first_map_point is not None: + # Map point should be near trajectory (within hundreds of meters) + distance_from_origin_xy = np.linalg.norm(first_map_point[:2]) # Only check X, Y + distance_from_origin_xyz = np.linalg.norm(first_map_point) # Check X, Y, Z + + # Get first trajectory point for comparison + first_traj_point = self.rig.trajectory.poses[0].vec3 + + logger.info( + f"Map transformation verification: " + f"first lane center point: {first_map_point}, " + f"first trajectory point: {first_traj_point}, " + f"distance (X,Y): {distance_from_origin_xy:.2f}m, " + f"distance (X,Y,Z): {distance_from_origin_xyz:.2f}m, " + f"Z difference: {abs(first_map_point[2] - first_traj_point[2]):.2f}m" + ) + + # Warn if Z coordinate is too far from trajectory Z + z_diff = abs(first_map_point[2] - first_traj_point[2]) + if z_diff > 10.0: # Z coordinate difference exceeds 10 meters + logger.warning( + f"Map Z coordinate may not be correctly aligned with trajectory. " + f"Map Z={first_map_point[2]:.2f}m, Trajectory Z={first_traj_point[2]:.2f}m, " + f"difference={z_diff:.2f}m. This may cause route generation to fail." + ) + + logger.info(f"Successfully loaded map: {map_name} (transformed to local coordinate system)") + return self._map + except Exception as e: + logger.error(f"Error loading map: {e}", exc_info=True) + return None + + @property + def metadata(self) -> Metadata: + """Create and return Metadata object""" + if self._metadata is not None: + return self._metadata + + # Extract metadata from scene + scene_id = self.scene_id + + # Ensure rig is loaded + rig = self.rig + + # Extract camera ID list from rig + camera_id_names = [] + if rig and rig.camera_ids: + camera_id_names = [camera_id.logical_name for camera_id in rig.camera_ids] + + # Calculate time range + if self._scene is not None: + dt = self._scene.dt + length_timesteps = self._scene.length_timesteps + base_timestamp_us = getattr(self, "_base_timestamp_us", 0.0) + time_range_start = float(base_timestamp_us) / 1e6 + time_range_end = float(base_timestamp_us + length_timesteps * dt * 1e6) / 1e6 + else: + time_range_start = float(rig.trajectory.time_range_us.start) / 1e6 + time_range_end = float(rig.trajectory.time_range_us.stop) / 1e6 + + # Create metadata + from datetime import datetime + import uuid + + self._metadata = Metadata( + scene_id=scene_id, + version_string="trajdata_direct", + training_date=datetime.now().strftime("%Y-%m-%d"), + dataset_hash=str(uuid.uuid4()), + uuid=str(uuid.uuid4()), + is_resumable=False, + sensors=Metadata.Sensors( + camera_ids=camera_id_names, + lidar_ids=[], + ), + logger=Metadata.Logger(), + time_range=Metadata.TimeRange( + start=time_range_start, + end=time_range_end, + ), + ) + + return self._metadata + + +def discover_from_trajdata_dataset( + dataset: UnifiedDataset, + scene_indices: Optional[list[int]] = None, + smooth_trajectories: bool = True, + base_timestamp_us: int = 0, +) -> dict[str, TrajdataDataSource]: + """ + Create TrajdataDataSource dictionary from trajdata UnifiedDataset. + + Args: + dataset: UnifiedDataset instance + scene_indices: List of scene indices to load (if None, load all scenes) + smooth_trajectories: Whether to smooth trajectories + base_timestamp_us: Base timestamp in microseconds + + Returns: + dict[scene_id, TrajdataDataSource] + """ + if UnifiedDataset is None: + raise ImportError("trajdata is not installed. Please install it to use this function.") + + data_sources = {} + + if scene_indices is None: + # Get indices for all scenes + # Use dataset._scene_index to get scene count (refer to trajdata_artifact_converter.py) + # len(dataset) may not equal scene count, so use _scene_index + if hasattr(dataset, '_scene_index'): + num_scenes = len(dataset._scene_index) + logger.info(f"Got {num_scenes} scenes from dataset._scene_index") + elif hasattr(dataset, '__len__'): + # Fallback: if _scene_index doesn't exist, try using __len__ + try: + num_scenes = len(dataset) + logger.warning( + "Using len(dataset) to get scene count, this may be inaccurate. " + "Consider checking if dataset._scene_index is available." + ) + except (TypeError, NotImplementedError): + logger.error("Cannot determine scene count: dataset has neither _scene_index nor supports __len__") + return data_sources + else: + logger.error("Cannot determine scene count: dataset has no _scene_index attribute and doesn't support __len__") + return data_sources + + if num_scenes == 0: + logger.warning("No scenes found in dataset, please check dataset configuration") + return data_sources + + scene_indices = list(range(num_scenes)) + logger.info(f"Will load all {num_scenes} scenes (indices: 0 to {num_scenes-1})") + + for scene_idx in scene_indices: + try: + scene = dataset.get_scene(scene_idx) + scene_id = scene.name + + data_source = TrajdataDataSource.from_trajdata_scene( + scene=scene, + dataset=dataset, + scene_id=scene_id, + smooth_trajectories=smooth_trajectories, + base_timestamp_us=base_timestamp_us, + ) + + data_sources[scene_id] = data_source + logger.info(f"Loaded scene: {scene_id} (scene index: {scene_idx})") + + except Exception as e: + logger.error(f"Failed to Load {scene_idx}: {e}") + continue + + return data_sources + + +class LazyTrajdataArtifactLoader(dict[str, TrajdataDataSource]): + """ + Lazy-loading wrapper for trajdata artifacts. + + Instead of loading all scenes at startup (which is slow), this class + loads scenes on-demand when they are first accessed. This significantly + speeds up worker startup in multi-worker mode. + """ + + def __init__( + self, + dataset: UnifiedDataset | None = None, + dataset_config: dict | None = None, + trajdata_config_path: str | None = None, + scene_indices: Optional[list[int]] = None, + smooth_trajectories: bool = True, + base_timestamp_us: int = 0, + ): + """ + Initialize lazy loader. + + Args: + dataset: UnifiedDataset instance (if provided, use it directly) + dataset_config: Config dict for creating UnifiedDataset (if dataset not provided) + trajdata_config_path: Path to trajdata config file (for error messages) + scene_indices: List of scene indices to load (if None, all scenes) + smooth_trajectories: Whether to smooth trajectories + base_timestamp_us: Base timestamp in microseconds + """ + if dataset is None and dataset_config is None: + raise ValueError("Either dataset or dataset_config must be provided") + + self._dataset = dataset # Will be created lazily if None + self._dataset_config = dataset_config + self._trajdata_config_path = trajdata_config_path + self._scene_indices = scene_indices + self._smooth_trajectories = smooth_trajectories + self._base_timestamp_us = base_timestamp_us + self._loaded_scenes: dict[str, TrajdataDataSource] = {} + self._scene_id_to_index: dict[str, int] = {} + self._lock = threading.Lock() + self._total_scene_count: int = 0 + + # Store scene count if scene_indices is provided + if scene_indices is not None: + self._total_scene_count = len(scene_indices) + + # Don't create dataset or build mapping here - do it lazily on first access + # This avoids slow UnifiedDataset creation at worker startup + logger.info( + f"LazyTrajdataArtifactLoader initialized (UnifiedDataset and mapping will be created on-demand)" + ) + + def _ensure_dataset_created(self) -> None: + """Create UnifiedDataset if not already created.""" + if self._dataset is not None: + return # Already created + + if self._dataset_config is None: + raise ValueError("Cannot create UnifiedDataset: no config provided") + + logger.info("Creating UnifiedDataset (first access, this may take a while)...") + import time + create_start = time.perf_counter() + self._dataset = UnifiedDataset(**self._dataset_config) + create_elapsed = time.perf_counter() - create_start + logger.info(f"UnifiedDataset created in {create_elapsed:.2f} seconds") + + # Determine scene_indices if not provided + if self._scene_indices is None: + if hasattr(self._dataset, '_scene_index'): + self._scene_indices = list(range(len(self._dataset._scene_index))) + else: + logger.warning("Cannot determine scene indices, lazy loading may not work correctly") + self._scene_indices = [] + + # Update scene count for __len__() + self._total_scene_count = len(self._scene_indices) if self._scene_indices else 0 + + def _build_mapping_if_needed(self) -> None: + """Build scene_id to index mapping on first access (lazy, only when needed).""" + if self._scene_id_to_index: + return # Already built + + # Ensure dataset is created first + self._ensure_dataset_created() + + logger.debug("Building scene_id to index mapping lazily (will build on-demand)") + # Don't build mapping here - build it lazily when scenes are accessed + # This avoids loading all scenes at startup + # The mapping will be built incrementally as scenes are accessed via __getitem__ + + # If we have scene_indices, we can pre-populate the mapping structure + # but we'll only get scene names when scenes are actually accessed + # For now, we'll build the mapping lazily in __getitem__ + + def __getitem__(self, scene_id: str) -> TrajdataDataSource: + """Load scene on-demand when first accessed.""" + with self._lock: + # Ensure dataset is created (lazy creation) + self._ensure_dataset_created() + + # Check if already loaded + if scene_id in self._loaded_scenes: + return self._loaded_scenes[scene_id] + + # If mapping has this scene, use it directly + if scene_id in self._scene_id_to_index: + scene_idx = self._scene_id_to_index[scene_id] + logger.debug(f"Lazy loading scene {scene_id} (index {scene_idx})") + scene = self._dataset.get_scene(scene_idx) + + data_source = TrajdataDataSource.from_trajdata_scene( + scene=scene, + dataset=self._dataset, + scene_id=scene_id, + smooth_trajectories=self._smooth_trajectories, + base_timestamp_us=self._base_timestamp_us, + ) + + self._loaded_scenes[scene_id] = data_source + return data_source + + # Mapping doesn't have this scene yet - search lazily through indices + # This is still lazy - we only search until we find the matching scene + logger.debug(f"Searching for scene {scene_id} in dataset (lazy search)...") + for scene_idx in self._scene_indices: + try: + scene = self._dataset.get_scene(scene_idx) + found_scene_id = scene.name + # Add to mapping for future lookups + self._scene_id_to_index[found_scene_id] = scene_idx + + # If this is the scene we're looking for, use it + if found_scene_id == scene_id: + data_source = TrajdataDataSource.from_trajdata_scene( + scene=scene, + dataset=self._dataset, + scene_id=scene_id, + smooth_trajectories=self._smooth_trajectories, + base_timestamp_us=self._base_timestamp_us, + ) + self._loaded_scenes[scene_id] = data_source + return data_source + except Exception as e: + logger.warning(f"Failed to get scene {scene_idx} while searching: {e}") + continue + + raise KeyError(f"Scene {scene_id} not found in dataset") + + def __contains__(self, scene_id: str) -> bool: + """Check if scene_id exists (lazy - only checks already discovered scenes).""" + # Don't build full mapping - just check what we've discovered so far + # This avoids loading all scenes + with self._lock: + return scene_id in self._scene_id_to_index + + def __len__(self) -> int: + """Return number of available scenes.""" + # #region agent log + import time + import os + import json + len_start = time.perf_counter() + try: + with open(DEBUG_LOG_PATH, "a") as f: + f.write(json.dumps({"sessionId": "debug-session", "runId": "run1", "hypothesisId": "E", "location": "trajdata_data_source.py:1119", "message": "__len__ called", "data": {"worker_id": os.environ.get("WORKER_ID", "unknown"), "pid": os.getpid(), "total_scene_count": self._total_scene_count, "has_dataset": self._dataset is not None, "has_mapping": bool(self._scene_id_to_index)}, "timestamp": int(time.time() * 1000)}) + "\n") + f.flush() + except Exception: + pass + # #endregion + # Return stored count if available, otherwise 0 (will be updated when dataset is created) + if self._total_scene_count > 0: + return self._total_scene_count + # If dataset is already created and mapping is built, use that + if self._scene_id_to_index: + return len(self._scene_id_to_index) + # Otherwise return 0 (will be determined when dataset is first accessed) + return 0 + + def keys(self): + """Return scene IDs (lazy - only returns already discovered scenes).""" + # Don't build full mapping - just return what we've discovered so far + # This avoids loading all scenes + with self._lock: + return self._scene_id_to_index.keys() + + def values(self): + """Return loaded data sources (only returns already loaded scenes).""" + # Don't load all scenes - just return what's already loaded + return self._loaded_scenes.values() + + def items(self): + """Return (scene_id, data_source) pairs (only returns already loaded scenes).""" + # Don't load all scenes - just return what's already loaded + return self._loaded_scenes.items() diff --git a/src/utils/alpasim_utils/trajectory.py b/src/utils/alpasim_utils/trajectory.py index 9bc96e2b..d2aee297 100644 --- a/src/utils/alpasim_utils/trajectory.py +++ b/src/utils/alpasim_utils/trajectory.py @@ -206,6 +206,18 @@ def clip(self, start_us: int, end_us: int) -> Trajectory: start_us = max(start_us, self.time_range_us.start) last_timestamp_us = min(end_us, self.time_range_us.stop) - 1 + # Check if start and end are the same (single timestamp case) + if start_us == last_timestamp_us: + # Single timestamp case: just interpolate to that one timestamp + single_pose = self.interpolate_pose(start_us) + return Trajectory( + timestamps_us=np.array([start_us], dtype=np.uint64), + poses=QVec( + vec3=single_pose.vec3[np.newaxis, :], + quat=single_pose.quat[np.newaxis, :], + ), + ) + # interpolate the start and end poses, retain the poses in between first_pose, last_pose = self.interpolate_to_timestamps( np.array([start_us, last_timestamp_us], dtype=np.uint64) @@ -213,16 +225,12 @@ def clip(self, start_us: int, end_us: int) -> Trajectory: is_between_start_and_end = (self.timestamps_us > start_us) & ( self.timestamps_us < last_timestamp_us ) - if start_us == last_timestamp_us: - poses = [first_pose] - timestamps_us = [start_us] - else: - poses = [first_pose, *list(self.poses[is_between_start_and_end]), last_pose] - timestamps_us = [ - start_us, - *self.timestamps_us[is_between_start_and_end], - last_timestamp_us, - ] + poses = [first_pose, *list(self.poses[is_between_start_and_end]), last_pose] + timestamps_us = [ + start_us, + *self.timestamps_us[is_between_start_and_end], + last_timestamp_us, + ] return Trajectory( timestamps_us=np.array(timestamps_us, dtype=np.uint64), diff --git a/src/wizard/configs/base_config.yaml b/src/wizard/configs/base_config.yaml index 4563dd1e..89ea4537 100644 --- a/src/wizard/configs/base_config.yaml +++ b/src/wizard/configs/base_config.yaml @@ -262,9 +262,11 @@ runtime: sensorsim: # how many rollouts can run on a single worker at once n_concurrent_rollouts: 2 + skip: false driver: n_concurrent_rollouts: 14 + skip: false physics: n_concurrent_rollouts: 14 diff --git a/trajdata_config_example.yaml b/trajdata_config_example.yaml new file mode 100644 index 00000000..cc2a00b0 --- /dev/null +++ b/trajdata_config_example.yaml @@ -0,0 +1,18 @@ +desired_data: + - nuplan_test + +cache_location: "/dir/to/trajdata/cache" # Trajdata cache location + +incl_vector_map: true +rebuild_cache: false +rebuild_maps: false +require_map_cache: false +num_workers: 1 +desired_dt: 0.5 +verbose: true + +data_dirs: + nuplan_test: "/dir/to/nuplan-v1.1" # nuplan-v1.1 + +# scene_indices: [0] + diff --git a/user_config_parallel.yaml b/user_config_parallel.yaml new file mode 100644 index 00000000..7c19db2e --- /dev/null +++ b/user_config_parallel.yaml @@ -0,0 +1,290 @@ +enable_autoresume: false +nr_workers: 1 + +endpoints: + controller: + n_concurrent_rollouts: 14 + skip: true + do_shutdown: true + driver: + n_concurrent_rollouts: 14 + skip: true + physics: + n_concurrent_rollouts: 14 + skip: true + sensorsim: + n_concurrent_rollouts: 4 + skip: false + sensorsim_cache_size: '4' + trafficsim: + n_concurrent_rollouts: 14 + skip: true + +scenarios: + # - scene_id: 2021.08.30.16.16.44_veh-40_00779_01088-e5d2a01ab5b0562a + # assert_zero_decision_delay: false + # group_render_requests: true + # cameras: + # - logical_id: CAM_F0 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_L0 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_L1 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_L2 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_R0 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_R1 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_R2 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_B0 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # egomotion_noise: + # cov_orientation_x: 0.0 + # cov_orientation_y: 0.0 + # cov_orientation_z: 0.0007 + # cov_x: 0.05 + # cov_y: 0.05 + # cov_z: 0.0 + # enabled: false + # time_constant_orientation: 5.0 + # time_constant_position: 3.0 + # egopose_interval_us: 500000 + # control_timestep_us: 500000 + # force_gt_duration_us: 20000000 + # min_traffic_duration_us: 5000000 + # n_rollouts: 1 + # n_sim_steps: 10 # max steps 10 + # physics_update_mode: NONE + # planner_delay_us: 0 + # route_generator_type: MAP + # send_av_messages: false + # send_recording_ground_truth: false + # time_start_offset_us: 00000 + + # - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689-5d5cef2e5d6b5d6b + # assert_zero_decision_delay: false + # group_render_requests: true + # cameras: + # - logical_id: CAM_F0 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_L0 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_L1 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_L2 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_R0 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_R1 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_R2 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_B0 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # egomotion_noise: + # cov_orientation_x: 0.0 + # cov_orientation_y: 0.0 + # cov_orientation_z: 0.0007 + # cov_x: 0.05 + # cov_y: 0.05 + # cov_z: 0.0 + # enabled: false + # time_constant_orientation: 5.0 + # time_constant_position: 3.0 + # egopose_interval_us: 500000 + # control_timestep_us: 500000 + # force_gt_duration_us: 20000000 + # min_traffic_duration_us: 5000000 + # n_rollouts: 1 + # n_sim_steps: 10 # max steps 10 + # physics_update_mode: NONE + # planner_delay_us: 0 + # route_generator_type: MAP + # send_av_messages: false + # send_recording_ground_truth: false + # time_start_offset_us: 00000 + + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689-a3f2ea7187975b13 + assert_zero_decision_delay: false + group_render_requests: true + cameras: + - logical_id: CAM_F0 + first_frame_offset_us: 0 + frame_interval_us: 500000 + height: 1080 + width: 1920 + - logical_id: CAM_L0 + first_frame_offset_us: 0 + frame_interval_us: 500000 + height: 1080 + width: 1920 + - logical_id: CAM_L1 + first_frame_offset_us: 0 + frame_interval_us: 500000 + height: 1080 + width: 1920 + - logical_id: CAM_L2 + first_frame_offset_us: 0 + frame_interval_us: 500000 + height: 1080 + width: 1920 + - logical_id: CAM_R0 + first_frame_offset_us: 0 + frame_interval_us: 500000 + height: 1080 + width: 1920 + - logical_id: CAM_R1 + first_frame_offset_us: 0 + frame_interval_us: 500000 + height: 1080 + width: 1920 + - logical_id: CAM_R2 + first_frame_offset_us: 0 + frame_interval_us: 500000 + height: 1080 + width: 1920 + - logical_id: CAM_B0 + first_frame_offset_us: 0 + frame_interval_us: 500000 + height: 1080 + width: 1920 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + control_timestep_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 5000000 + n_rollouts: 1 + n_sim_steps: 10 # max steps 10 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 00000 + + # - scene_id: 2021.09.09.17.18.51_veh-48_00657_00876-baf1301534ea54d6 + # assert_zero_decision_delay: false + # group_render_requests: true + # cameras: + # - logical_id: CAM_F0 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_L0 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_L1 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_L2 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_R0 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_R1 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_R2 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # - logical_id: CAM_B0 + # first_frame_offset_us: 0 + # frame_interval_us: 500000 + # height: 1080 + # width: 1920 + # egomotion_noise: + # cov_orientation_x: 0.0 + # cov_orientation_y: 0.0 + # cov_orientation_z: 0.0007 + # cov_x: 0.05 + # cov_y: 0.05 + # cov_z: 0.0 + # enabled: false + # time_constant_orientation: 5.0 + # time_constant_position: 3.0 + # egopose_interval_us: 500000 + # control_timestep_us: 500000 + # force_gt_duration_us: 20000000 + # min_traffic_duration_us: 5000000 + # n_rollouts: 1 + # n_sim_steps: 10 # max steps 10 + # physics_update_mode: NONE + # planner_delay_us: 0 + # route_generator_type: MAP + # send_av_messages: false + # send_recording_ground_truth: false + # time_start_offset_us: 00000 \ No newline at end of file diff --git a/user_config_parallel_all_scenes.yaml b/user_config_parallel_all_scenes.yaml new file mode 100644 index 00000000..608b078a --- /dev/null +++ b/user_config_parallel_all_scenes.yaml @@ -0,0 +1,46256 @@ +enable_autoresume: true +nr_workers: 1 # 4 个 worker 并行执行 + +endpoints: + controller: + n_concurrent_rollouts: 14 + skip: true + do_shutdown: true + driver: + n_concurrent_rollouts: 14 + skip: true + physics: + n_concurrent_rollouts: 14 + skip: true + sensorsim: + n_concurrent_rollouts: 2 + skip: true + sensorsim_cache_size: '4' + trafficsim: + n_concurrent_rollouts: 14 + skip: true +extra_cameras: + - logical_id: camera_front_wide_120fov + rig_to_camera: + rotation_xyzw: + - -0.49929397355810856 + - 0.5039939168301356 + - -0.4972939976976715 + - 0.49939397235113037 + translation_m: + - 1.65897811 + - -0.01443456 + - 1.51539499 + +scenarios: + - scene_id: 2021.05.25.14.16.10_veh-35_00083_00485=0c318d7923d15b78 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_00083_00485=24567f5ad57455c4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_00083_00485=34f30283d3bd53ec + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_00083_00485=431ae29947e95c26 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_00083_00485=45e8b10f95925c47 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_00083_00485=4b594a8e80915943 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_00083_00485=5d3e45ad38ef5b9c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_00083_00485=83fd1c194c0c5441 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_00083_00485=c9b12b21fa7c57fd + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=025b657634505df3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=067d731005885300 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=08b6a130aaa35629 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=1893fb783df95146 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=218adf8c450058eb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=368cb65e8fef57b7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=41d7b533797c5209 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=4c775cb227b0519d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=4ccc9e33aa795ef1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=644b16fd65f956b8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=6fbe0e06902e5304 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=6fed9368351f54d5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=78b4153a6d3e5b33 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=82cd122751085a80 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=9215555823945665 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=98017c16248a5f54 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=a41f538fa8e25be0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=c50b9b8950ba5347 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=dd9b1479609c5c59 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=e83be8437b0c5862 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=f02b15cc225b5d9a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01100_01664=fe800ded24045b44 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01690_02183=0b57b00279885fd4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01690_02183=0c77bbb199f3589f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01690_02183=19488eb3301f5d26 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01690_02183=2313aa310e16503d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01690_02183=2cd1545c4c835ead + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01690_02183=30f09e001cf55013 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01690_02183=3debd3d86b5850dd + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01690_02183=54e1cb577c0a5f7e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01690_02183=75f9d978b4d757a2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01690_02183=a0e9cbedca0a56b7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01690_02183=b6968f154bfb5a5d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01690_02183=d3badb5f8c125e12 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01690_02183=db180d0c665454aa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_01690_02183=ebfb953d479d5982 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_02482_02649=6507522e38405857 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_02482_02649=6f11adda2af357ff + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_02482_02649=8e9f743d92c05d10 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_02482_02649=b92ea560ae10562b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_03373_03550=27d74807a89a5268 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_03373_03550=741ee8b9ea3059a5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_03373_03550=80a4b14aef3f5a52 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_03373_03550=b133316a0e795993 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_03373_03550=c6c94bd6691c5008 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_03373_03550=d1065c7c84e054ae + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_03373_03550=e76485315c2c5028 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_04097_04328=0868436794795421 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_04097_04328=19d3dfdf0d2d5b6f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_04097_04328=35ceec8930305499 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_04097_04328=47e3bbbd82b2583b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_04097_04328=4e0667aa6ead5e7d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_04097_04328=56886aeb0f685bea + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_04097_04328=8898650e43665faf + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_04097_04328=cc853dd8697f51b3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_04097_04328=d90cd23a434f5c55 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.16.10_veh-35_04097_04328=dbf083df3f5c55d7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_00934_01067=08ac82bf0eeb5661 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_00934_01067=12d283af921a5f09 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_00934_01067=748779bcdb5b5a49 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_00934_01067=974d5c00402f55aa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_00934_01067=c159f0c331075464 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_00934_01067=cdb1d43f01565d9c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_03764_04034=0578756b879c55d0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_03764_04034=23ee145aa4de582b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_03764_04034=2d4d907377f35695 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_03764_04034=5e9e8c31277d5edc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_03764_04034=60b5ba011ea65e68 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_03764_04034=9326163d4c9c5d16 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_03764_04034=d59310a4fd6e5fde + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_03764_04034=f5a9eba40a9055f3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_04059_04203=14c2bb3737ab519c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_04059_04203=4314c162a57f568e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_04059_04203=47359dd210e254ea + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_04059_04203=5395d42cc65e5c06 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_04059_04203=6225b347244658c1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_04059_04203=68ba9a9b2d6f572d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_04059_04203=bca002ce93bd5997 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_04059_04203=d398c8ceafe050be + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.24.08_veh-25_04059_04203=de03efda68e65021 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.26.37_veh-27_04122_04279=303d452ddd2d58d1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.26.37_veh-27_04122_04279=63d80f7499fc5784 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.26.37_veh-27_04122_04279=690d5fcd5dd056dc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.26.37_veh-27_04122_04279=d2c77b46ecee58f9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.14.26.37_veh-27_04122_04279=fcb4f430c99050b3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_00625_00855=247ba5f9646c5528 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_00625_00855=290a914d4ef15443 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_00625_00855=5c34deba76605c7b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_00625_00855=bdb0947d0c835022 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_00625_00855=d44d7aacab755892 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_00625_00855=e6eeac307f6d507d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_01478_01643=415b05ca44da5fbb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_01478_01643=4c7c3a0a401d5f38 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_01478_01643=6233d1b3e62a5772 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_01478_01643=7ffee2481b68517c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_03499_03671=00ff8eeb53cc598b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_03499_03671=18375bbfe4c85ae3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_03499_03671=5bbd26efb97658ec + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_03499_03671=ade979d99d51517f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_03499_03671=d5ece6235301571f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_04027_04200=2115a02d06035ce0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_04027_04200=3fb360a01b775e07 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_04027_04200=46ce401b30ac56e9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_04027_04200=476c37463b4f580e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_04027_04200=4bdff78fdccd5f6d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_04027_04200=5abe25231fd05639 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_04027_04200=81c70798936b5140 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_04027_04200=906d7e590245576a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_04027_04200=e905f33735985cfe + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_04027_04200=ec75cc0ff5825fb9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_04027_04200=efe0cf18491855e6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_04027_04200=fdc126183c355692 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_04463_04606=1fd4a838b258571f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_04463_04606=6a85f61bdde35d74 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_04463_04606=6e3c7a34388e5ae3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_04463_04606=d88fdf29aeed58f5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.15.59.03_veh-30_04463_04606=f0a6222ab3e55174 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.16.37.23_veh-25_00005_00217=3bc4c087ab1a50a3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.16.37.23_veh-25_00005_00217=512b6941e1335e0f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.16.37.23_veh-25_00005_00217=5c5f0c06d7035bb7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.16.37.23_veh-25_00005_00217=60681597a59d5cf9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.16.37.23_veh-25_00005_00217=8deec95251e95c2d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.16.37.23_veh-25_00005_00217=92e3a80a8f775ce2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.16.37.23_veh-25_00005_00217=d753a5379cc15b69 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.16.37.23_veh-25_03311_03550=40d43586b1195366 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.16.37.23_veh-25_03311_03550=46aea2dcb1485353 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.16.37.23_veh-25_03311_03550=d0fc0e92a9e4552f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_01654_01850=0a0d91d55b0757f8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_01654_01850=1370cea130165b51 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_01654_01850=2959d5dbe8235765 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_01654_01850=34d782c068c855be + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_01654_01850=40df19739f215995 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_01654_01850=77155a60b2ae5e75 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_01654_01850=c1e1661e600c570e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_01654_01850=cecd27d3ba0e54fd + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_01905_02121=0965108c193757a9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_01905_02121=18d04df0d7e25316 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_01905_02121=4749b2486da65268 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_01905_02121=517e199220ca522b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_01905_02121=624f26fa47485b3d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_01905_02121=789af91cd1755b7e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_01905_02121=9d5e6089bd0d5caf + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_01905_02121=d83c3b7416f3577e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_02723_02902=0c437f9a102c57f4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_02723_02902=2a2cb941f34b5bc4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_02723_02902=4196ab00e95e532d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_02723_02902=42c7526fc6845005 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_02723_02902=84ed0a5827f656d8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_02723_02902=94a3b8d43f515d6e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_02723_02902=981ceb0924575bc3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_02723_02902=e4b6a49b32545d95 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_02723_02902=f42258b638fc5b64 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_02723_02902=fe4e5fdf88195cfa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_04111_04288=0498b27fee425645 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_04111_04288=1270261ff182534f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_04111_04288=3f11ac11755857c2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_04111_04288=8051c60f20705909 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_04111_04288=95005e9d60b05d1d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_04111_04288=ecf10edba55e5595 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.17.54.41_veh-35_04967_05098=1baf6c7677a95a6a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.18.38.25_veh-25_04058_04186=649ee93e67cc58bb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.18.38.25_veh-25_04058_04186=b07f7a319de35f9a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.05.25.18.38.25_veh-25_04058_04186=cdc030cdbc9153ae + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_00233_00609=007845701f635565 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_00233_00609=09c56525e8e853a8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_00233_00609=169528411ca85ba4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_00233_00609=4bc793d4a9ef5860 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_00233_00609=5282504f73a759b9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_00233_00609=5b61b9072cad5dbc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_00233_00609=8d90099a801d5682 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_00233_00609=abe4fa26de85552d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_00233_00609=ae5377e5ebf65f45 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_00233_00609=b60b509ee8ba5197 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_00233_00609=be7331d3f05e5d16 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_00233_00609=d9c4acb18e675789 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_00233_00609=ddc904ff3be05595 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_00233_00609=e0865304e2b95eaa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_01100_01227=0f206a62842b59b2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_01100_01227=23d0ae8aedf8537b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_01100_01227=7bbb6cfc4f135e50 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_01100_01227=b111bb8716b756d2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_03526_03712=0c3c4cd553475d3a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_03526_03712=8eda03e314a456a4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.12.02.06_veh-35_03526_03712=da53dac7558e563d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_00073_00426=4e1b2f2152b551e2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_00073_00426=508209397e8f5714 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_00073_00426=6389fb6f9d675e3b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_00073_00426=896f25f6f25e52e0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_00073_00426=9c68b0b158bb5d03 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_00073_00426=a916c0c016825703 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_00073_00426=b4ec906c4dbe5735 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_00789_00999=0fa9d28a2e58550c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_00789_00999=153733002b5a5d25 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_00789_00999=72080a4a90a65d4b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_00789_00999=878f3ddae1b7550f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_00789_00999=ce09ed938df353d1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_00789_00999=f74148c131c15381 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02419_02561=05850e3460015579 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02419_02561=4f5d9ee9c2915058 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02419_02561=6535e6022ba0547c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02419_02561=77218354c5c25657 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02419_02561=be2d7d1ddb305428 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02419_02561=f976da772a435bd5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02572_02855=11118a8c74d95c5c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02572_02855=96af2f9a0f9352ab + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02572_02855=b27841ee318f5d92 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02572_02855=bdef1564d4565c48 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02572_02855=e29b049a9bf3509c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02572_02855=f84b6dbc1cd35f61 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=0854af027e06530a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=0aa8c67f04b75a41 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=0ba42ee3c2555502 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=110bec4c6d2153d7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=1693d395bec753ae + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=26b80207f01e593f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=44cedd469129548d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=639352b63c715c1f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=6be41ab63cf05b6e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=6fc4fc2702305dfa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=7ccfef5040b359df + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=869f688594fc58c1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=9b58f5bd4e995a93 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=a572d70690f75ad4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=afa8102c20685ec5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=b27e2139fbb959fa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=b6a62a2356885962 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=c72c3c003bc95aab + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=d1e9fac71909545f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=eb5ef679c80959fe + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.13.55.17_veh-35_02866_03582=f92ecd09fdf45404 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_00712_00855=ac24fb00e61a5da2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_00712_00855=ebc294355ca753b0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_02571_02742=9a89dccc70835d69 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_02571_02742=ff94ab2c81a25745 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_02943_03220=013d05a439b95210 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_02943_03220=0393e11b085a5cc2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_02943_03220=1434146a1ab75426 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_02943_03220=4495218e41b35f25 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_02943_03220=56da58294b3d53c5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_02943_03220=61046515c9885bf5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_02943_03220=6debfcfccc75589c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_02943_03220=76375396b08e5143 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_02943_03220=c2736d03415f515b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_02943_03220=d91f0c28683e52da + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_02943_03220=f1b802f6e9a559af + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_02943_03220=f5b613e3fa03593d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_02943_03220=fcb45b2aa29356d9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_03860_03992=21e4dfb3741d529f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_03860_03992=82b52ede639d544d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_03860_03992=95472243c6245fec + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.17.06.58_veh-35_03860_03992=a7ad6a154d2051bd + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.18.47.39_veh-35_00123_00246=67c2aef1f35a523e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.18.47.39_veh-35_00123_00246=ae33eb2afd655f7d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.18.47.39_veh-35_00257_00492=4db7ecab510656e1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.18.47.39_veh-35_00257_00492=6e67504ab65f5314 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.18.47.39_veh-35_00257_00492=70becaf36f845b1d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.18.47.39_veh-35_00257_00492=9a524d13e6795a95 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.18.47.39_veh-35_00257_00492=e10fd359f695575f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.18.47.39_veh-35_00257_00492=e6ff81ab83355450 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.18.47.39_veh-35_00257_00492=f2644280215250cd + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.18.47.39_veh-35_00503_00777=15454d7562d45fe6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.18.47.39_veh-35_00503_00777=1bf45a481f1d52e3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.18.47.39_veh-35_00503_00777=378d79a6bf715912 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.18.47.39_veh-35_00503_00777=3f2cec87b5ad5d96 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.18.47.39_veh-35_00503_00777=4a0ba18cefc05c63 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.18.47.39_veh-35_00503_00777=98867b3fc7a95c24 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.18.47.39_veh-35_00503_00777=a454e18ca33d5cb7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.18.47.39_veh-35_00503_00777=ced5e9f4d448524e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.03.18.47.39_veh-35_00503_00777=e4d88f52d2b45609 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.13.53.26_veh-26_00492_00696=0eb28cf3dad95c46 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.13.53.26_veh-26_00492_00696=407bc420086a58f6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.13.53.26_veh-26_00492_00696=5012cae5e4fc57a1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.13.53.26_veh-26_00492_00696=58cf6aaf126b5727 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.13.53.26_veh-26_00492_00696=626b5dc253965ecb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.13.53.26_veh-26_00492_00696=69d2af69b1b75698 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.13.53.26_veh-26_00492_00696=786f447064055cfd + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.13.53.26_veh-26_00492_00696=78f941ea974f5084 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.13.53.26_veh-26_00492_00696=9100530861d851b0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.13.53.26_veh-26_00492_00696=b411a654aa215f1b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.13.53.26_veh-26_00492_00696=c38664c4b23853a3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.02.02_veh-38_02398_02848=066c0c3f45915cba + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.02.02_veh-38_02398_02848=0c8b9f08bfa25dc2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.02.02_veh-38_02398_02848=105e820419e05224 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.02.02_veh-38_02398_02848=4f7b03242ab05a2d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.02.02_veh-38_02398_02848=65729e98f81a526e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.02.02_veh-38_02398_02848=7fc1ce68acb7562c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.02.02_veh-38_02398_02848=9b3a284d78f458f3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.02.02_veh-38_02398_02848=9bfa838de21f5d25 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.02.02_veh-38_02398_02848=a06715f1cb8358c0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.02.02_veh-38_02398_02848=a4c23fa815945fe3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.02.02_veh-38_02398_02848=b043b68462d7540c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.02.02_veh-38_02398_02848=b1e78f926612520e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.02.02_veh-38_02398_02848=b49e63992eee56b1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.02.02_veh-38_02398_02848=c37a081992495a0e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.02.02_veh-38_02398_02848=c4e94b7583555176 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.02.02_veh-38_02398_02848=c87001c4251e559a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.02.02_veh-38_02398_02848=cce49307530e5b60 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.02.02_veh-38_02398_02848=d32f8367252b53b1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.02.02_veh-38_02398_02848=d484aff53cd1589f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.10.57_veh-16_02438_02580=62c5045db3c159aa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.10.57_veh-16_02438_02580=78c9157a55905d81 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.10.57_veh-16_02438_02580=92838ad73bf95b3a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.15.10.57_veh-16_02438_02580=f24b703a3f14583f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_00022_00368=04aa69f18d255c96 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_00022_00368=114f66c4cf785eab + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_00022_00368=1509901c10495792 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_00022_00368=260d8dc1970256a0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_00022_00368=33c7945f43795064 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_00022_00368=53d3787367c75240 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_00022_00368=64a417561b53530f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_00022_00368=73a3a880d8d8522c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_00022_00368=74693ae387e752fa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_00022_00368=89751620b3555ef8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_00022_00368=9d18c2e4a9c35be7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_00022_00368=ba6136583b6254e2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_00022_00368=be861669f7ff5de4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_00022_00368=d0785c050c1350e7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_00022_00368=e973ce0e5d605df5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_01415_01821=19a718729d3a5e37 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_01415_01821=253adcf13a3f5c15 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_01415_01821=5099c20d468f5cf4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_01415_01821=8feb2ae5cc2451c3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_01415_01821=b64b160540265465 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_01415_01821=c0ea178930145138 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_01415_01821=d2c7bb24957c56ad + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_01415_01821=ed8294474bc35b6c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_01415_01821=f36dbc258c8b5e17 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_01415_01821=fc6dc98b89a95817 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=0c38a8ace1f5548e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=330166def5a35f4d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=4291f43bae455b98 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=49119e0bd9335681 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=5816a23cfee25d4e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=5fe06174763b5c36 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=7cdcc814be255d9f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=8a2c1d34f9df5213 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=8cd3d83dd4825865 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=94652fa0c64d5846 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=ac07a96cae965e88 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=b24575ef9d575fb4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=b2f336de7d295a8b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=b87c15c9f6cf54eb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=ba84537a483f508a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=bc949c2045ca5537 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=c38fcc20f071501a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=d8c6aedcb54a56fb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=ea141bd5c40259de + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.29.11_veh-38_03263_03766=f79916e26eef5b74 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.57.59_veh-26_00016_00484=0722adecc3d45ac4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.57.59_veh-26_00016_00484=0fc28fe43e5d5693 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.57.59_veh-26_00016_00484=1081728e06ca5239 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.57.59_veh-26_00016_00484=12f96c65436e56bf + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.57.59_veh-26_00016_00484=13cfa80cabf85b80 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.57.59_veh-26_00016_00484=2f9b9537ea1c5018 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.57.59_veh-26_00016_00484=41da8ea7c14754d2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.57.59_veh-26_00016_00484=6efb5186a9e55a68 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.57.59_veh-26_00016_00484=806b014bc8c15160 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.57.59_veh-26_00016_00484=9baf3c1d42b25070 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.57.59_veh-26_00016_00484=a164681774715cea + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.57.59_veh-26_00016_00484=b826ee4aedc95b0c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.57.59_veh-26_00016_00484=bbb7e4525bd05d3d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.57.59_veh-26_00016_00484=beeb0c78917a528a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.57.59_veh-26_00016_00484=c2ae8e85ce2052ff + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.57.59_veh-26_00016_00484=d32336b185505124 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.16.57.59_veh-26_00016_00484=de4ace24443b5b2d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.18.03.27_veh-14_00620_01581=075154c90a0a5d7c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.18.03.27_veh-14_00620_01581=08a80ada64475443 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.18.03.27_veh-14_00620_01581=1741767a7646583a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.18.03.27_veh-14_00620_01581=179ea24426e95029 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.18.03.27_veh-14_00620_01581=4d38d745131c5de1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.18.03.27_veh-14_00620_01581=4f8d9bfa869553bb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.18.03.27_veh-14_00620_01581=5d47863332065766 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.18.03.27_veh-14_00620_01581=6083bfcb495d5f9a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.18.03.27_veh-14_00620_01581=7e9101f6d01a53e0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.18.03.27_veh-14_00620_01581=831a14b3c0bb5c50 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.18.03.27_veh-14_00620_01581=9ee5cb5e3908569a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.18.03.27_veh-14_00620_01581=aa1f80806fa35b9f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.18.03.27_veh-14_00620_01581=b50b8f11d75a5cb0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.18.03.27_veh-14_00620_01581=c8629b9dd63e56ad + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.18.03.27_veh-14_00620_01581=ed4bcfb05c405bac + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.18.03.27_veh-14_00620_01581=f8e2454674f75e0f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.18.03.27_veh-14_00620_01581=fa1a3ccade2e50bf + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.18.03.27_veh-14_00620_01581=fd4c64e354f953bd + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_00369_00601=2b3b9bb9f6525589 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_00369_00601=661d0a5bf2735f03 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_00369_00601=69c991e96f74541f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_00369_00601=6e163d828a555eee + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_00369_00601=7d5618d384ac5071 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_00369_00601=953aea8a2a085404 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_00369_00601=aaf90b3acdce5063 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_00369_00601=ced4cade3bea53e7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_00369_00601=db94e239ea1a5468 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_00369_00601=f6db2434c92450b8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=04e3e7c9b4bf5ddf + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=0774f6d8e3185794 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=08e03654c0ca5151 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=0d7d0361dc665d25 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=0f622aef14545f59 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=10c1bbbe7d805eba + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=1347c91c511a5918 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=15165972946050eb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=1712f51cf5df564a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=1786ef7edac65502 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=1f2bbc5cb66b523a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=250e6e2e6a9d5ee8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=2c21ad85949653a6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=3078139bae8e592d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=33e37f9d760a56b1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=457acf87bc885550 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=4b9627827aff5013 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=5a8855c7c104596c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=5cbb02f3e0e253e5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=5e96a7620956567a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=5f78b2fcada85eef + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=6021973f81a75e0b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=6532afe679315809 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=68643a176fcb5c7c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=6892e067e25257f8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=763821f100605f76 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=7bbacd116bd75f85 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=806b0f2b2ade5454 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=80df9e4f79c65d4d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=83873a51bef051ac + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=8564551c362e5f26 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=8790ecedb8ac580e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=8aae579b8090538a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=8b1ba99df5d05f8b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=8fbca2950de45a7c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=926d8c9ced715a42 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=927b73fea33f5218 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=9334f5a33c07587a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=95ee5b14fb3a5ce0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=9a594a58c8125976 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=9dff2b84ff305fff + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=a5a4a6add0d05113 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=a6229e66c0e656d8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=a862b4e7cbc05869 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=ad84af7b33615884 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=b5ca533bca505ceb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=c0d4412fa9f15f5b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=cb61f2ea159355a0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=cc8a7b88b06b56c2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=cce0795c7ff05129 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=d11b9fcd004e5270 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=d3484ba53e775a66 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=d4278d63cd605813 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=d6353a288d0b545d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=d7f6204c325d53fe + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=d8338aefbb73570f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=e1ea05ca230f5c42 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=e2e6c22bce7f59fc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=e61699cda2f15e01 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=e776468d9bf65a8a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=e933d70dd378598f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=eb527d130d8d5e33 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.20.24.43_veh-38_03385_04952=f253fd0891d3562a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.21.16.05_veh-14_00957_01198=48f9e483baaf58a0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.21.16.05_veh-14_00957_01198=50a0fd7b031e5ca6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.21.16.05_veh-14_00957_01198=a04628cdd3f25947 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.21.16.05_veh-14_00957_01198=a9853ab9c01c53d2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.21.16.05_veh-14_00957_01198=c3d5c730ba905b86 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.21.16.05_veh-14_00957_01198=c768a604b14e5956 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.21.16.05_veh-14_00957_01198=ef300f8a9cf254bc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.21.16.05_veh-14_00957_01198=fd3b8f88745c5c2d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.21.47.53_veh-35_00280_00424=0eae7eacff765533 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.21.47.53_veh-35_00280_00424=2640335fd6565b4f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.21.47.53_veh-35_00280_00424=3e429827093e538d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.21.47.53_veh-35_00280_00424=6abe0ed266f258d9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.21.47.53_veh-35_00280_00424=6f7355de329659f2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.21.47.53_veh-35_00280_00424=8a2df3fb1632552a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.21.47.53_veh-35_00280_00424=9ad434ec99685d35 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.06.28.21.47.53_veh-35_00280_00424=f4da0138413c595a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.16.14.23.37_veh-45_00015_00132=2ac5f9fae5a95215 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.16.14.23.37_veh-45_00015_00132=2cae5f08e11a5dbd + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.16.14.23.37_veh-45_00015_00132=36a229f658875a2e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.16.14.23.37_veh-45_00015_00132=45f13336bbd35146 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.16.14.23.37_veh-45_00015_00132=4cac9f6cd85a5b47 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.16.14.23.37_veh-45_00015_00132=5fadffd02da256e5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.16.14.23.37_veh-45_00015_00132=650c7a9e7ea45062 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.16.14.23.37_veh-45_00015_00132=9fdd329b72e85179 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.16.14.23.37_veh-45_00015_00132=a1adc0fae78f5a3f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.16.14.23.37_veh-45_00015_00132=e0d14f6cb7df526e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.16.14.23.37_veh-45_00015_00132=e393bc5cafe95872 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.16.14.23.37_veh-45_00015_00132=f289e368449b517b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00610_00771=059ca66ac38a5c28 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00610_00771=1a1f73871bea5afa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00610_00771=27cf243155ac526c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00610_00771=5bb6cc197a7455e4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00610_00771=65fd7014a79b5cba + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00610_00771=910198c6086a5a34 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00610_00771=96587a61c6c05d71 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00610_00771=9f4f46e620785407 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00610_00771=ac04f9fd4233550c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00610_00771=b81d52bf71365207 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00610_00771=c133861a233a51de + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00610_00771=cdc6e3f7dcb25376 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00610_00771=e1886e081b945907 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00784_00867=335576eae9705bfc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00878_01104=04daf401ec185f96 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00878_01104=0a571473239f5c89 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00878_01104=257d737fc3865fd1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00878_01104=647a42b4e5075f16 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00878_01104=702320a088cf5d53 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00878_01104=70da6b21101d555f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00878_01104=9a95d2419f1e592a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00878_01104=a42cc34c8a985b67 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00878_01104=d3cd01aa67de516f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00878_01104=e5dc48dd83585491 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00878_01104=e656eb8f3cdf590c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00878_01104=f68aaf95d7825182 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00878_01104=f9c0cc538bb457c8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_00878_01104=fd1e4ae4c102553c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_01116_01336=0a21cbc65e5b514f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_01116_01336=0ba54149d1575f95 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_01116_01336=2dad1998a320527d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_01116_01336=4c684da98f405857 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_01116_01336=6f1be4d182475bc8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_01116_01336=af5ebe3ccf8f50ed + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_01116_01336=ef81756601bc569f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.13.45.25_veh-40_01116_01336=f6f14df95f6c52af + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00334_00419=237739df15ff58cb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00334_00419=72cb0bed47ab5464 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00334_00419=c2915f2ac7f55f97 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00334_00419=cb50b764d69557b9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00334_00419=d31d38e1a2305147 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00439_00835=02f75336f9f55e4f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00439_00835=04fafb805d465314 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00439_00835=0a8c2aac609d5a04 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00439_00835=1ca75f05f31d51cc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00439_00835=2bc38f766c8851fa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00439_00835=3ca2e3e846e75813 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00439_00835=4109b79d84ea5053 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00439_00835=443b9c514efc5829 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00439_00835=537935a8e7b653f2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00439_00835=638b83e65dd259f8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00439_00835=673a88a4037f5b6b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00439_00835=7fb88e704c1a5cca + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00439_00835=c054f473288d5515 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00439_00835=d50b69bed8f2570c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00439_00835=da137494751e500f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00439_00835=fa7f471f19aa5806 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00885_00986=4211afd0df14524c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00885_00986=9f105aba36355fe1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.14.54.34_veh-40_00885_00986=b95ff3bc9cf45e47 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00256_00716=047b56d34f1d5aa0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00256_00716=190808cc16cc53af + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00256_00716=43a4f01072795345 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00256_00716=5403d4e6179a5354 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00256_00716=6dcb6aa97a07588b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00256_00716=8ff8246f69f75f6a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00256_00716=91f7454802305af8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00256_00716=b30ee22eca0a57ef + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00256_00716=c28f3febaf635777 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00256_00716=ea4d19ff25ac52f6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00256_00716=eb15f0d956eb5ac4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00779_01088=0d1b753fd19f55cb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00779_01088=521247f86d7f57c0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00779_01088=639b55d4b2b65d0a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00779_01088=7f47c3fca9075a31 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00779_01088=a9c15f8aabb65b09 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00779_01088=ab226645ee6f54aa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00779_01088=c3ace87d2f985eaa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00779_01088=c89f33e9f07d5aa8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00779_01088=d0884d449b2959fe + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00779_01088=d1971f367cb85683 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00779_01088=e131caa356115811 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00779_01088=e1f58cff32225d3a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00779_01088=e5d2a01ab5b0562a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00779_01088=f78a67043d9e5477 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_00779_01088=fb5265ab37085422 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_01099_01351=0d9243e74a1a501a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_01099_01351=0f24ec666e145cab + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_01099_01351=112db94505025ec5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_01099_01351=2bd04a0902095129 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_01099_01351=4b3d6fc60b815701 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_01099_01351=58ad6156b5895541 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_01099_01351=9af711dfa6eb5952 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_01099_01351=af0e1a3043ba51c6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_01099_01351=cd0b91f235e25b76 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.08.30.16.16.44_veh-40_01099_01351=e699fb1c75b95e57 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00221_00299=026bb114391d5b81 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00221_00299=45c3a52706c555df + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00221_00299=b1a1b2a18fa4504f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00221_00299=cedd32ec31e45cd9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00221_00299=d2098ab3fc1953b3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00221_00299=d782b032259d5cc0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=00c489998dd4555c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=0bd98f90f42350a3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=1218b6a218b750d8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=13848a5be84f5a4a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=18d8181124185dfa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=20403b65d87d5e5a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=26e7a31dd615509c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=2c76300c674f5769 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=3388246402ca591e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=4849a426de8e5d24 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=4b721ff0b7025f21 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=50e5a63ba7ac5d51 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=52d3f15d6ca75701 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=581e219460ef5789 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=6d08dce7cfaa5035 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=704527beccac5701 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=7d51b80c3aa25109 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=8659bfccd4195fb6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=982b57b1c7c7503a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=994ab680895a55d2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=ab845dd1ff3c522d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=d436fd792f365847 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=e87f90ab04a25be9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00322_00895=f227c6775ba75451 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00960_01115=0c9105d8ad6a5f52 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00960_01115=0d35a8e6a98a5759 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00960_01115=135337bf847b5726 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00960_01115=47e64379df6b55b2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00960_01115=73864df7d2d25214 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00960_01115=814b5e08c20e57af + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00960_01115=8d5d769b1f1e5802 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00960_01115=b53b172e95895a12 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_00960_01115=dcf3da6b34935bc8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_01298_01492=2e54d786ec095896 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_01298_01492=2ea6bdf1e8905fd8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_01298_01492=4c3547b853675e66 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_01298_01492=6012210b020c53a9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_01298_01492=7ef36a2139b45d9a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_01298_01492=bc7ae4f9eced56c9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_01298_01492=cbbf59be3a4e555d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_01298_01492=d91edafc567a5fcc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_01298_01492=d9b577262eed5ceb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_01503_01761=1b5521472b795718 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_01503_01761=4b3c6a95987c552d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_01503_01761=79a151c333745253 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_01503_01761=87339a4d32305504 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_01503_01761=a7fa8bccce9253cb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_01503_01761=a98e0fd4eee7534a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_01503_01761=bb85e87e90ae52ec + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_01503_01761=bba5d587cab25dfa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.14.18.22_veh-48_01503_01761=be0064dac5f85957 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00098_00328=51c2558524435a31 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00098_00328=85936ccd1b405f4c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00098_00328=ab74b3b32d8c5006 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00098_00328=b337627936ea5488 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00098_00328=c3ef435d900256c1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00098_00328=e133b313fabc56b4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00098_00328=e84ff3e29bc05254 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00098_00328=f6a8d6a5c5b355d0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00574_00646=3e7bec3b1c4359b6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00574_00646=5102468ad3745c60 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00657_00876=00f49d71f0eb507b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00657_00876=215c38293c335e25 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00657_00876=7780e502545a5df7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00657_00876=798842f0b1c253b4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00657_00876=7bce82e059a05030 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00657_00876=7d4c548895955e0d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00657_00876=88f3df2443c55e59 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00657_00876=baf1301534ea54d6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00889_01147=08e025b8ab6253bc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00889_01147=3b8d6a01f5705389 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00889_01147=5883b0e7c7215e80 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00889_01147=62667ead92a35fbd + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00889_01147=6782b9c3686f58f3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00889_01147=6b258d7ddf7d53f3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00889_01147=8f741adb793f51c9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00889_01147=cf1c7170df175256 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_00889_01147=f2a8ed3f01f15ef3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_01173_01237=10ae805f0be95c1f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_01173_01237=2556a5c923c95128 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_01248_01450=3ae3cf56296b5861 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_01248_01450=4de72cf1449b51c8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_01248_01450=583e9cc4115258e4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_01248_01450=60e8f2447c205324 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_01248_01450=6e983b745cb9535b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_01248_01450=794b439e9922527b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_01248_01450=8686e685b08a5c3e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_01248_01450=879d4e4e0d2b5386 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_01248_01450=8993f8b000855b17 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_01248_01450=9fe3ed9455355edb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_01248_01450=a567ea679ba056ce + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_01248_01450=b7598f311c365e95 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_01248_01450=baf0c6e99bec57db + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_01248_01450=fe4459e9f02052d3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_01462_01552=1975d15fde2955ff + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_01462_01552=a4f2f32aa59f53b9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.17.18.51_veh-48_01462_01552=e9bb1dab462252e9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00555_00731=160e6592389759c5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00555_00731=1e4f2f231ac0540e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00555_00731=463d1cf17f915536 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00555_00731=80f6c94fed0c5519 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00555_00731=a64a3e4f2048576d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00555_00731=daf38cecd5045cf6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00555_00731=e0094ac69a8955fb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00743_01071=152679f2edce5c73 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00743_01071=1b18327179f15a8f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00743_01071=1ecea4b911675b72 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00743_01071=3c7c1b09e9625732 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00743_01071=4dd9d92ade255f95 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00743_01071=5c786c10eb7f57da + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00743_01071=6d2b59f78d995d9c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00743_01071=7d664c7260d45737 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00743_01071=8eefb96f7e5f598e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00743_01071=9d1d720d0e2e511e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00743_01071=b814c5b773165d87 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00743_01071=bddb70b4743352ce + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00743_01071=e14f1ffbe6f856e8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_00743_01071=e6bdb406a21e55ba + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_01340_01425=3756dc24f9e65fd7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_01340_01425=5487bbfde69354cb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.04.06_veh-40_01340_01425=ae878998fecb50a5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00427_00556=08a8fc71ab1b57c2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00427_00556=4c1a6bbf7aaa5228 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00427_00556=4d94decfbcd35ae6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00427_00556=631115d8e54d58fc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00427_00556=75d9973be85e50f0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00427_00556=a0d88b07304b5398 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00427_00556=cd4e4564d732554e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00569_00903=1be3fd906c435f85 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00569_00903=1c078ca2e3625bb0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00569_00903=46cd5885206b5c6d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00569_00903=83472e2adb545cd5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00569_00903=8d21608fa8c354f1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00569_00903=b5d5d15093af5638 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00569_00903=cbbc4cdfaf2e5106 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00569_00903=daea2a5f018858f6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00569_00903=e6dae41a69575555 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00969_01184=0eb6987fdc9b5213 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00969_01184=653ebb370df45ca5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00969_01184=8317ed430d8e50c3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00969_01184=9114a3a480dd5466 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00969_01184=cdda15bd879d5a30 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00969_01184=d224548a04525f2c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00969_01184=f1849aa89eed53d1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_00969_01184=f42bdbb0a30c5854 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_01622_01766=5016bf8ca2ee554c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_01622_01766=6e944f00e04c5f1c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_01622_01766=d2cac33c80f45434 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_01622_01766=df240e44ad0d5c3c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.09.18.29.25_veh-39_01622_01766=e7295df63d0751d2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00077_00153=171e0bea742d52d0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00077_00153=19227b35432f567e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00077_00153=1b88b298d405518e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00077_00153=9f521d00c3ef55b7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00077_00153=cfa1a5ff80355988 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00077_00153=e03da8beb33a5e06 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00077_00153=f424ee234e385b95 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00077_00153=fbd06f49da055ea8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00180_00342=0221ed2a1c495f23 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00180_00342=21e98ee0ac165e2c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00180_00342=2c5cbab120595d79 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00180_00342=345f39f8de925db9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00180_00342=392a50db492b536e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00180_00342=52d9d533ca4e5980 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00180_00342=592f536375e755b6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00180_00342=59ea5c8c067e57e7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00180_00342=6eac1c0e2bbd57bb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00180_00342=77160cf8a6b8581d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00180_00342=93ed1cf3d95a5dab + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00180_00342=a51fda3f10da5432 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00180_00342=afe83cb6c0ae5f67 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00180_00342=bd4dac2ccde55c08 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00180_00342=c45fc2b353c655af + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00180_00342=d08754ee7c5c5949 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00180_00342=f419cea88ed9500b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00180_00342=f754138d3e3e5fd5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00180_00342=fd001bff97c155b3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00630_00818=1424caab55de5db7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00630_00818=193b39b2ec4f53af + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00630_00818=39cbed62434a528b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00630_00818=5fffee1a19495dc6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00630_00818=92427e4a55475ba6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00630_00818=c9150b81da695ae9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00630_00818=fb2402a506065225 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00860_01069=01329f4a29285dfe + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00860_01069=0802a51b0a1d512c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00860_01069=17ea7a2cc29957fa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00860_01069=2eb015a011ac5fa2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00860_01069=7be1e4f2c85e50a8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00860_01069=d4358e3962b758ce + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_00860_01069=e69be869445455c7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_01510_01591=2d9d3d15e7f25716 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_01510_01591=3e8e85cf14c65da8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_01510_01591=4dd1ab3a667b5074 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_01510_01591=71674e79275f5abb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_01510_01591=7a6d3719323a5188 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_01510_01591=ae50b115259f5a24 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.13.53.10_veh-42_01510_01591=ddc5aacc5d785804 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00032_00186=0a77356a8ee85133 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00032_00186=167fd80fa8635037 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00032_00186=4972962184a75fa7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00032_00186=4f67484c73e2503a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00032_00186=5491f2f619e25dfb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00032_00186=5865085ba43752de + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00032_00186=5abd4abd73db5739 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00032_00186=6a6362156db75390 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00032_00186=6de8e1962fc4559a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00032_00186=6fdde744b66451da + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00032_00186=8179a26d74615228 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00032_00186=834a23e3dd25542c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00032_00186=83e895f722575452 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00032_00186=8451437af5ba59ea + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00032_00186=975c802f6f175888 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00032_00186=b23be6b0d9765878 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00032_00186=c354c8cf3c975581 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00032_00186=c7cb2e43b2d053b7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=089e3eac4f7e5c5c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=0a06f8a3204d5e11 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=0cc24c1449cd54f9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=0d8754f6d53d5968 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=13cd1cf21a4f5acb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=1c31e37ce65b52d9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=1db7c81f96855ce9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=2d0334f7e7d75853 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=3380d56c05ba594b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=3f269e7b5ced51fa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=47da19c4edbe5b95 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=5cfbf7afa66458c3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=6828c3caaaca56e1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=727ed49214315cd6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=9a24a904a324581d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=a3882e6ae8635832 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=a44db880afe95be7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=b474c79361415cb0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=b7c35b12755c5d44 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=bb30019d8f645e62 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=bf00c76f25185b83 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=bf4c97f6024b5029 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=c484b85e7b07535c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=c7a44a2e52bc5e22 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=dee99345e2015845 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=e6056b57c0515735 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=e9b43b140b1d54bf + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=e9cfc98fdc09590a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=f2592c08589e5398 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=f820630d5f0a50ed + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=fa9a6007ed205fe7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_00297_00935=fc0fc7649a335d27 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01111_01448=389bfba2e25f581b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01111_01448=3c4e1784d9295821 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01111_01448=4e3f39fa6dfc5d12 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01111_01448=51552f78760d5a11 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01111_01448=53f8bc4012fe5f29 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01111_01448=758cc7a721c2546d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01111_01448=77cf9dfc36c35df7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01111_01448=7f93aad83fb15871 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01111_01448=a09e4156f577568a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01111_01448=a3c4e4bf10d65ddb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01111_01448=afbbcee34f1850fd + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01111_01448=beecbff2fd37592e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01111_01448=cbf53151339658cb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01111_01448=d01b6e67a995589c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01111_01448=d1ef1e42fa15573d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01111_01448=eeab709ca6e05d14 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01609_01687=44f75400f3a15c14 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01609_01687=4ef621a8318b5085 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01609_01687=6d3bb2ecca3e54b4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01609_01687=8237f47b224952b4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01609_01687=878665ca715b53d3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01609_01687=8a4a0c6823cd5e33 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01609_01687=8c156f5b675b5657 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01609_01687=f0b762b8c08b5ff0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.14.39.34_veh-42_01609_01687=ff89c9bf77dc58ce + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.12.03_veh-42_01037_01434=13e6cd945bf95a1f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.12.03_veh-42_01037_01434=16ee6602bb5c5e99 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.12.03_veh-42_01037_01434=2a34f4d0aefc5039 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.12.03_veh-42_01037_01434=5f402207dd7d5977 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.12.03_veh-42_01037_01434=65271f4c14985330 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.12.03_veh-42_01037_01434=6c5d84e81aca5755 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.12.03_veh-42_01037_01434=70ee383e3b335c16 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.12.03_veh-42_01037_01434=77761cd0edf15867 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.12.03_veh-42_01037_01434=7edfabe116e25844 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.12.03_veh-42_01037_01434=8d39d3f85647574c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.12.03_veh-42_01037_01434=8fe49f5c68d65801 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.12.03_veh-42_01037_01434=a8fb178e35d25d73 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.12.03_veh-42_01037_01434=b5b8d20688385790 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.12.03_veh-42_01037_01434=e6a94b91b19f5315 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.12.03_veh-42_01037_01434=ed90bab84c475e4f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.12.03_veh-42_01037_01434=fe6105aa925d5621 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.47.30_veh-45_01199_01391=037b976caae85af5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.47.30_veh-45_01199_01391=0481cf2b75f1532f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.47.30_veh-45_01199_01391=09cd7b3746d65a79 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.47.30_veh-45_01199_01391=30e7a7c93a225968 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.47.30_veh-45_01199_01391=365c0937de9d5885 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.47.30_veh-45_01199_01391=526b66c665085401 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.47.30_veh-45_01199_01391=551afc276a1a5ab3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.47.30_veh-45_01199_01391=708d081d555a5aa7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.47.30_veh-45_01199_01391=bf896d504b4356c7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.47.30_veh-45_01199_01391=cebd7d74024b5cce + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.47.30_veh-45_01199_01391=dd162898ecf351d4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.15.47.30_veh-45_01199_01391=edf7e758c7075ce8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.16.20.27_veh-08_02435_02525=0abc30416c5a59cd + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.16.20.27_veh-08_02435_02525=3acfdef9ef305e77 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.16.20.27_veh-08_02435_02525=6451d6a270c75f58 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.16.20.27_veh-08_02435_02525=76e0272a57f55674 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.16.20.27_veh-08_02435_02525=7cdcf11e211759cf + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.16.20.27_veh-08_02435_02525=c1e76b8992fa5182 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.16.20.27_veh-08_02435_02525=ea8ce810e307587d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.17.40.09_veh-45_02539_02745=13ae6351239c5343 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.17.40.09_veh-45_02539_02745=14576a845ffc521a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.17.40.09_veh-45_02539_02745=1b25edea36205814 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.17.40.09_veh-45_02539_02745=1eade5af9ee65696 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.17.40.09_veh-45_02539_02745=47e0ff3bc36a5f69 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.17.40.09_veh-45_02539_02745=5a12337425265ea1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.17.40.09_veh-45_02539_02745=661ce644db6d5546 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.17.40.09_veh-45_02539_02745=6704953640e55b83 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.17.40.09_veh-45_02539_02745=6f393be3019c508a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.17.40.09_veh-45_02539_02745=8227648b1da95adb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.17.40.09_veh-45_02539_02745=93bdcee4c814567c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.17.40.09_veh-45_02539_02745=a96abad3a09753c5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.17.40.09_veh-45_02539_02745=b5155b952c645ce0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.17.40.09_veh-45_02539_02745=f79b805ec2435c98 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_00289_00398=0d40059cfdf75e7a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_00289_00398=25c1569ea1d753f2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_00289_00398=2c978eb63fec5d2a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_00289_00398=45ebc34cbe405c3e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_00289_00398=ac808bd1bfac5425 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_00289_00398=c038901b4a0259ab + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_00289_00398=c39f042bbc0256ba + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_00289_00398=ef1f8e45b9f05e4f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_00289_00398=f3e0463f3cf4505e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_01088_01192=62eac0a6b7e05fbf + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_01088_01192=91afe72955de5b85 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_01221_01380=1b96821ba3425e3b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_01221_01380=2ff39958d9f35279 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_01221_01380=3fd7c487c29f53bc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_01221_01380=b683672d37cc5001 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_01438_01677=008b419a63b75917 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_01438_01677=2258bd346b3f5376 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_01438_01677=3d37ed78124057a1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_01438_01677=4161016e65df5b37 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_01438_01677=5cf43f51d45c552f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_01438_01677=6d2178f2992f5d22 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_01438_01677=909655c780e152ac + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_01438_01677=9104884bcb915c08 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_01438_01677=96cb1a2412095a90 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_01438_01677=9839a7913075581e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_01438_01677=9c03b730a5725c00 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_01438_01677=adccdafdfc3d5e0c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.12.04_veh-42_01438_01677=c169cf799b165800 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_00472_00711=132d1ec43fc058e1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_00472_00711=1457dddd3ea65845 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_00472_00711=1d63ddad646b5496 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_00472_00711=365808b195f35dff + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_00472_00711=8cc8fe63227d5c07 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_00472_00711=a2978bba82bd5751 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_00472_00711=cf31c5ada8c353bc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_00472_00711=d395fa715d3e58c7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_00472_00711=e09bc42b58285147 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_00472_00711=e5599a8884235d93 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_00472_00711=f0b6499b393152be + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_00472_00711=ffde3cc525b75021 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=077c80ecaed0548f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=0d77009a20f25175 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=10909749099354e6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=17296f6032025ecc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=19e90f2757b25f38 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=1b301e5f9ede59d7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=1fe5f6af95e15489 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=216b31d31f085114 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=262c4400163e5d8e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=3770407dcc67520c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=42629decf8ad5328 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=426cc213a80352f9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=43c9ac6f2bf95da0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=43f586c2ca4b5929 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=4c24c3efe0e4519d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=50613cf56a8d5a38 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=51e4c182629c50a7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=572e6c81e32958f2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=595909c413ac56dd + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=5b1a620dcd675298 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=5b4cbfe57b9b524b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=5d3573d6da7952d3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=657ea52878935352 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=69938a4507ba5419 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=6b50fb6bf8265936 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=6b6afd7690245e14 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=7217a95078bf52f2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=7767ce3fbd5f5f50 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=790a5a0973815ab3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=79e7ccb136775266 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=8135a67aa74e586c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=81a726148d245594 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=8799520f3ff95bfc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=888913e0978f559b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=89e02236312d5038 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=9551ef5e14315cc0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=9696c1f82bc05ffc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=99213b077bdf516b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=a08215e27d775f96 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=a2839b1b4f0352e4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=a3d10c0a5a835300 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=a8455a10df085d45 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=a899eed59bf85d84 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=ac140df715d5573b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=b9aa102f4d7b5751 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=b9d14f59883a5496 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=bdad96248e575296 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=be63913f07ee5245 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=c099ebaef4c251d6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=c240593c969a5cfc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=c28b41c8410f5465 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=c64ddb8e7b675aa3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=c665621fe4e455cb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=c672b42254b3556d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=cd0a001eb97a5c88 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=cdc9eb7c7ddb5b08 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=d0d94d5dca655084 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=d33c6db306f35ef9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=d3dcb57d3c385f19 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=d6a60e406ebc5b01 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=d743862c9c555961 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=d870256a3b185659 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=e45572ab63ef5deb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=e85416da86d4567f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=ea1302023ad258ff + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.27.01_veh-45_01749_03230=f6268af57ef35a2b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=02015675e4585611 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=06fbdeb141965cca + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=1ca03ed089925396 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=33ecaddeb5735faf + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=3b5422b60c4f5c4b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=4302a0a4b9f05b61 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=458e833803315b4f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=4abb45d9ee1a5c5c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=5ddfd1fe80af5ceb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=714a2012b2a75d4f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=7956c9ed4b855859 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=8bb939128dfd5f7d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=9a675656c3c85f4c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=9b1bea0cc0d75583 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=a067e1b873c8534d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=a08bb182c3d558da + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=a1d7b6056b4b5566 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=a9609780217c5831 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=bd70654aee0f54a6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=c687799dac8d5aa2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=c887e4bc08f85aa5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=caa3170f8c3b5cfe + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=d93d307c5aeb5338 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=ded4ce0e91b4596a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=e31131deed6656ea + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=e511376fdf3250e5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=f3e32c06633756e9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=f9349f5d723b5421 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.19.49.00_veh-42_00990_01609=fde7abb615895be2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.21.13.37_veh-42_00172_00347=7084e524e59c50ab + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.21.13.37_veh-42_00172_00347=7900996a42f35f67 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.21.13.37_veh-42_00172_00347=a425dd8a1b5552db + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.16.21.13.37_veh-42_00172_00347=f3512ae175b45844 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00238_00320=0278f1a2ae3b5ae5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00238_00320=cf50ffa22c81555d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00238_00320=cfb755b8d37458ac + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00337_00504=00016f8b45c25a1d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00337_00504=0ab7e69f15735883 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00337_00504=32d85d373126537e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00337_00504=4624907fdacb5038 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00337_00504=6648a1c53b8c5994 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00337_00504=a55fdc98ef8057e5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00337_00504=e051405f88c05270 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00528_00992=0879b546c3cb5615 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00528_00992=0bdc177e43cf5df8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00528_00992=1f211666d4465388 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00528_00992=297a54df537c5317 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00528_00992=3d6703caa0c951a8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00528_00992=6058f9d8998e5a95 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00528_00992=645e303a25a65190 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00528_00992=6781255a85605dd5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00528_00992=687da3cabde458b5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00528_00992=6e3cf172a2755fae + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00528_00992=96c8893a610b51ba + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00528_00992=987f5dced605588a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00528_00992=9e24f7a402a85804 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00528_00992=b036f9ef53cd5536 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00528_00992=caa0f73288d75ba7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00528_00992=d2dd81d9f7665fde + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_00528_00992=f5442665da9f554c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01059_01191=175f0101f12750b1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01059_01191=3d776c43acfd5327 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01059_01191=6eac35cd4c6e53b0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01059_01191=770c714d82535180 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01059_01191=dda361f4db52537a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01059_01191=f1e870d5d8275cac + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01202_01296=33197ac2a7445bd7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01202_01296=556283de632c5226 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01202_01296=af8dc1b01446555a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01202_01296=afbf26b6d3bb5bee + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01331_01485=1c4544c0876f5a08 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01331_01485=49ee466685265a80 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01331_01485=6659724ab0a8566c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01331_01485=8224a14715c2577b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01331_01485=a5ee1632a31556a1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01331_01485=a9c6cd5519815308 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01331_01485=f3493d3b23cd55c2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01331_01485=f5d9b1df3fef57ec + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01509_01628=49ae6840ff7f5e91 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01640_01743=0220967816915e94 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01640_01743=4ab74b20c99e5d20 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01640_01743=6ec2148215205936 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01640_01743=7db2c53b0e9e5971 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01640_01743=9b10283b8df6565e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01640_01743=9f839d5422315781 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01640_01743=aab517c2e5e75245 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.14.44.26_veh-28_01640_01743=cc934224447a5c86 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00601_00802=1666152446cc5da7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00601_00802=62108a4000e85dae + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00601_00802=77ae9dba6f05550d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00601_00802=8f273271b9eb537e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00601_00802=a3dd6d539acc5c9b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00601_00802=a8d904be723d5ab9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00601_00802=adfc4abb1c4d50b3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00601_00802=aec02ec2aec85c06 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00601_00802=af6ce3c064fa5a56 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00601_00802=c20397c103e65d12 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00601_00802=d46b1d647640578f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00601_00802=ee4a2e2de70a510b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00601_00802=fc0a60a9d8245aea + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00814_01101=192220ae5c0a54a6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00814_01101=4b3a1e85619e557f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00814_01101=6edc8f2bcb3054be + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00814_01101=700237dffc2d5be7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00814_01101=7272f8ee7e64591e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00814_01101=8e00c08f68af5357 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00814_01101=ad6af1cce80c5983 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00814_01101=b5ee0c4a00765073 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00814_01101=bebbdf5c01b85cf1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00814_01101=cc1862b24d0157bb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00814_01101=d89e9c599cf5571b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.15.23.04_veh-28_00814_01101=f93bfd9479fd52ee + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00331_00426=1f095494fe755244 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00331_00426=918d03455301591b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00438_00833=150d706a5add549a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00438_00833=1559a9e324d6519d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00438_00833=21b98219003453af + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00438_00833=377d556af9d25dab + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00438_00833=38b4ff11393c5dec + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00438_00833=6872fa29d1345d03 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00438_00833=697c73f258ef5745 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00438_00833=887e4d57da835b12 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00438_00833=c44755b18af45385 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00438_00833=d07fa319e6045a3d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00438_00833=d82f1b20a55d5bcd + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00438_00833=f3fd7b1cf6055ad5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00844_01218=0334cae9f1ef56ae + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00844_01218=035db9ac34715b07 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00844_01218=04cdd9195f885ac6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00844_01218=12f2dccfb88957f9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00844_01218=16d4835b75b05efb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00844_01218=511741d6df93540d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00844_01218=522b72a25cbb5ef9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00844_01218=c12b3554dcd655c0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00844_01218=cb53746741b25730 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00844_01218=ccd6fe2d044e5309 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00844_01218=e83f4b6e1dd25c90 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00844_01218=ea91c9a3a75f514c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00844_01218=ec097e80d5565caa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_00844_01218=f3c6560a01e55c94 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01268_01685=024d89a3e1e752dc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01268_01685=09df1da0af885ddd + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01268_01685=12d426c6727d507a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01268_01685=1947a9758e045ce9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01268_01685=223d02be29c65e81 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01268_01685=23803695a4c1547c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01268_01685=3d86e3fc3499578f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01268_01685=520f3dc854275784 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01268_01685=555226e5142f50ed + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01268_01685=59b4bb47cf6656cf + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01268_01685=5aa4b6dc8f0759b5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01268_01685=63b69a3c54e95277 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01268_01685=72cccfbb9c6f5e9e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01268_01685=85028441255156b3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01268_01685=9d423dea34235b41 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01268_01685=bb6cb09beb1e5e3f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01268_01685=c6c1dab6af9858f9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01268_01685=dc096269aef55bf0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01268_01685=fefad5f7d3405512 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01727_01833=81aa7cde0f3f5b68 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.18.19.40_veh-28_01727_01833=cfb9e8d047515e4c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00273_00514=2575048779565f0b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00273_00514=2d2b781181f156dc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00273_00514=32013abf6afd5d2e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00273_00514=618902d469b5516e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00273_00514=84ec7e450e205d8f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00273_00514=9897a102ee075dee + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00273_00514=9e4c1639be465a8a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00273_00514=bbc8e4799fe85548 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00273_00514=c8deb087395357c3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00273_00514=f264f464b21753de + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00273_00514=f665cf888bbd5595 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00540_00917=0573408e3cfb5130 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00540_00917=22642c0ae9605891 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00540_00917=26e8589d8c485726 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00540_00917=310fcecd57a95e06 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00540_00917=38b7b1afe2bf516b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00540_00917=56b80cb2ca2c5983 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00540_00917=5f09eaa4509f5997 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00540_00917=68df055f82485e95 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00540_00917=7e76a2b3918656f9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00540_00917=7fcf6a30139b5d3e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00540_00917=8a7750196bc65a14 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00540_00917=a35847734fc65508 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00540_00917=b12f2581dde259f4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00540_00917=b8d2227c06a351e4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00540_00917=cda381919f5e5dca + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00540_00917=d9b79e606e595700 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00540_00917=f2e0d7e15fa253f0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=02e3e6d3ecfc5240 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=04f8f8b4cf0c52e7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=1b01f89fe48355b6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=38db478c95eb5079 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=3bbe96de854e5ff3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=3eef6c6972dd538f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=47fae9a1708b5101 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=480325e1f5085385 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=51259bf89422548a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=59bb570b4290572d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=5d5cef2e5d6b5d6b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=66ca1ffcef4354e9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=70847cda9b3d5b07 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=79ecc8e6e5fa5dd5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=8b93118c77d25b5d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=973043f273bc5940 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=989ce8f4205654d3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=9e970e2a22da585c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=a3f2ea7187975b13 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=b0902109adea5e0f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=b3c7b9fbf4655722 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=b762ea96cfa75157 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=b9d45c43c2fd5165 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=be7c407443f15fec + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=d93e31dfb0c25be5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=decd6b1dd7f65e1e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=e80df2a74bfd5a22 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=e96c8f66dae15d60 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_00964_01689=ebd8d87ff33b5b7a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_01717_01824=4e496bfdb6b95697 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_01717_01824=71729b03a1e95896 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_01717_01824=c2790319345a58cf + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_02451_02708=2db75185de1d5763 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_02451_02708=36c9f5ba92385cee + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_02451_02708=6856c3ad77315d3c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_02451_02708=7f00cbbc74695c32 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_02451_02708=955af39177fe5ba1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_02451_02708=998c6c28d1475e78 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_02451_02708=b432924be8c151d8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_02451_02708=ca58b2e039305479 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_02451_02708=dcd3886f044a5e29 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_02451_02708=e6db7be94a175aec + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_02451_02708=ee9615c4b10d5ec9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_02451_02708=f4eec162c14e5bfa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_02911_03005=0b4dfcb47cb85e89 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_02911_03005=3c542be991515ccd + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_02911_03005=498c6f15e5c856bb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_02911_03005=815153cb27f95a7c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_03198_03360=0beacadfbc4553ea + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_03198_03360=1ed8702288c15895 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_03198_03360=1f67195591a95027 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_03198_03360=58c018c299d05214 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_03198_03360=7da6ba784b8b5ff0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_03198_03360=87124bde96ba59b1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_03198_03360=8d06ea883e7853a9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_03198_03360=a2c2e046132e5596 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_03198_03360=ba13a6004a0c5f8d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_03198_03360=f1ceb70bd72a5048 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.09.29.19.02.14_veh-28_03198_03360=fbf2eaa61abb5a2f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=062a9e3dd60955ce + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=1fa7d30105dd5ebd + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=2a30c259f67c561d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=38b01bebf6df5fb8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=38b08f2868a75306 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=465d43bf893d5e66 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=4da3c27db2495e9e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=50a5b2cbb4515594 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=649c1659d8975ae3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=69e0bc4a585d504a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=86aae04a66c45970 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=9389ef5de0935e29 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=ba7d6b30a3a15384 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=bf1184622f355af4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=cbadd750cbd6581b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=e045d3abc4e95f52 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=e0a1d14a2cea5d4a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=e36e9da57e1e5e32 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=e9505f806d8d5998 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=eea52ed765aa5977 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=f335a11369685b08 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00006_00398=fe74f3d6f5ea5283 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00422_00728=07846b829b3a575e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00422_00728=24b9908a6761529b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00422_00728=2b4fee42169a54a8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00422_00728=3e42abec9c495419 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00422_00728=4dba0d7ebbf95639 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00422_00728=62ebe5d1697f5b73 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00422_00728=6632c49f6f675b7b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00422_00728=6c3a055d6ac15aa9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00422_00728=79bb6b3243f151a6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00422_00728=9ee3c3a666d35a5c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00422_00728=a66018d8ad8f594d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00422_00728=b657fb1afb7c54f3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00422_00728=eac61acb69665f21 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00422_00728=eeba0804c2645281 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00422_00728=fb1d534ccf82583f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00772_00917=4cf608d9de4e5349 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00772_00917=54ab49005da25b3e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00772_00917=687fa6fce3ab5f91 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00772_00917=8187be48a9d95d91 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00772_00917=ba2ebab05dfd523e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00953_01126=015593741e7050f7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00953_01126=507a3844cf3051de + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00953_01126=5bb280e3aebe5a67 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00953_01126=62b0d1b0d5b35c44 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00953_01126=67debdeae60b5fa4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00953_01126=934c8ac938ad5dca + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00953_01126=a489c23d292e56fa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00953_01126=b1649a41e6155dd2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_00953_01126=c86c1d9c6e9c58aa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=0004474e9e3f5470 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=05d010f73fab576b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=097d35208fcb587c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=115d3d7bdadf52f8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=13ba9275e341525b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=1c0c94dbcd5359fc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=21b8742127e7523c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=22021c2141625fce + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=24817ec41ccb5f01 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=2b10974c7f7e5444 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=39215c6e71725031 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=4ceacfb6be565ab3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=4fd76c8d85845816 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=566cac9a7c0358ce + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=56783067f37c553f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=6042c6249f31509b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=661278fc8a9c57d3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=66b9427f41385b55 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=8294a047fcda5698 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=829e3a1622565a63 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=85570db66d605000 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=947b3794a3275a2c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=94c0ff5134d45dd1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=97080182e9a455b3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=9ebcea6ba47651f0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=a1848a01a20b5224 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=a82187d6e7805fa2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=a9956fd52aa15f39 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=b031e4b0aea8528b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=b50353ebaee65cbe + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=b92aaa468aa25958 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=be9298a106f552af + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=c2a93dd3494b5702 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=d392c806c0605f72 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=d79874fa9ba4558e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=e63d13e083695b1f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=efd6ba6db6db5f6c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=f016e2b6ac155a30 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=f5af09063e125bb2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_01245_02064=f86eb011b333505e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_02208_02394=09ce454826895686 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_02208_02394=263f5537c4f85b38 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_02208_02394=40843dcbac9d5c2e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_02208_02394=6743ebcc6f5259b8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_02208_02394=985e562ded345da4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_02208_02394=9a2894f199095f96 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_02208_02394=b04064e074f55bb0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_02208_02394=b5e3abde704b54c8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_02208_02394=c93008394b945625 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_02208_02394=ca62812a55ce5f0b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_02208_02394=d37afaf062ea5835 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_02208_02394=de56fef875ac5a5e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_02208_02394=e4b8bdb842ae567e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_02208_02394=e66b1160e38f5483 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.07.26.10_veh-52_02208_02394=fbf9670a3e82519c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00032_00170=2e67ddf209365112 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00032_00170=3eb063189dd15649 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00032_00170=4faa4706a50958e2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00032_00170=5c5a8066ceae51bc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00032_00170=6b68c09f87b85dc8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00032_00170=84b38cdaa93e5dcd + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00032_00170=863e343b2fe45cc1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00032_00170=a0be9e4c6cc15ec7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00032_00170=cd59c2696d01521a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00181_00574=0d7f280bf979592b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00181_00574=13b9787d163b5072 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00181_00574=1d3a143cf41f5d16 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00181_00574=39168e35ed085e11 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00181_00574=4eaf35cea96d5dd9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00181_00574=5a3a4277dc785511 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00181_00574=67077701cdd85c9d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00181_00574=7595830169065d37 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00181_00574=78c26c7e63c3534c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00181_00574=a8c2268684c35a80 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00181_00574=a9af1e73c9575428 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00181_00574=b9c124bdb19956b7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00181_00574=be6f90f06bc35be3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00181_00574=c2f56a56716f55e3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00181_00574=d7b1349fb4775cc1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00181_00574=ddc1271ea57154bc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00181_00574=e14711ef4d2f5000 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00181_00574=f082cf21642c5cbc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00181_00574=f9ed38d9ddfa531e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00612_00782=0fcb8c19983c51b6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00612_00782=3c8a95ec33f45af6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00612_00782=409711b03072566a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00612_00782=42eef0001e6c5498 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00612_00782=91c7e207e3395557 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00612_00782=b5668089b793502b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00612_00782=ccfe1da323ed53a9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00922_01296=3502b30911d75ed8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00922_01296=45c6be97d810541f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00922_01296=50628427853659fc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00922_01296=5b7d7e1a42c95cd7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00922_01296=7ae0a03be0c357d2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00922_01296=7c4757c2c9675f2b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00922_01296=8601b9cf8c6852f3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00922_01296=8c9e3fd944c051e3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00922_01296=8d3ac506e17050ba + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00922_01296=9b0a5826d2d357d8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00922_01296=b628faa4178d5eaf + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00922_01296=c20652fc6a78529b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00922_01296=c9aa2159bc3a50a0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00922_01296=d496c44726c35e33 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00922_01296=d81c4398a40b52b9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00922_01296=da6d3b6810995466 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_00922_01296=da751fd130625cce + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01430_01579=0a954cc695e751ab + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01430_01579=0fedf81df2db5b96 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01430_01579=281798a7d40559bb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01430_01579=3296619ed0855e31 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01430_01579=50fef67a5a9a5a4b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01430_01579=64a7186ab49b5cdc + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01430_01579=735587b14e39568c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01430_01579=73c6bf15d3cc58e4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01430_01579=abdf3c37dc03596c + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01430_01579=b227439005885966 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01430_01579=bc2532765f5a5262 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01430_01579=d551f73a1e4251aa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01430_01579=dad96574decb5a68 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01430_01579=e8850900bade58f6 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01590_01725=078bc1027dde5d1a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01590_01725=320446eca62c59fe + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01590_01725=424e3df76d475635 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01590_01725=8d3c8a698ac65342 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01590_01725=9e522849163c53b8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01590_01725=a5f411a2c379503d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01590_01725=c8aeadf284a05f44 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01590_01725=dd2d7e23754e58d3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01590_01725=f4495a91b9fb505d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=02b68b9cc51f506a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=069c6a5e408653ab + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=0ef7ecd9c0035467 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=0fa603b5789956f1 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=1f54430427975391 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=1f6d3d52a6685c15 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=20728d3e677b593d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=3276f87a152651f0 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=3a3297d21e905b02 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=3b4031def0f45d96 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=3d1bf2cf5ad151c7 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=430589fe41235469 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=5e02e80df7fe5f5b + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=667ea4f79faf5baa + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=67339e7fe4135722 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=69dec5959d7d53a9 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=69e8a01f073d5080 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=6a064f6f4529550a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=77424ed925b45c77 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=79ea7fb311c4574a + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=8551466c8066505e + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=8abfcd61303b52df + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=8be5583b37785664 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=96f6cde1205e5865 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=971d199e8b9b5e71 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=9a3778686fd058d2 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=9ba21cb552c35238 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=a67f68a6c9e85668 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=b958e6967993560f + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=c78f87b2bd4151d4 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=cd284af1ade75426 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=e072351fbbfd5765 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=e0cbc7ab694157a5 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=e9adc94d4e9c5fbb + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=ea23b2bb8e5756b8 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=ea32cdfc9478501d + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=efeac78f0da05463 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=ff44394af7265df3 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000 + - scene_id: 2021.10.06.08.16.17_veh-52_01949_02501=ffe92084016a5795 + assert_zero_decision_delay: true + cameras: + - first_frame_offset_us: -30000 + frame_interval_us: 500000 + height: 1080 + logical_id: camera_front_wide_120fov + shutter_duration_us: 30000 + width: 1920 + control_timestep_us: 500000 + egomotion_noise: + cov_orientation_x: 0.0 + cov_orientation_y: 0.0 + cov_orientation_z: 0.0007 + cov_x: 0.05 + cov_y: 0.05 + cov_z: 0.0 + enabled: false + time_constant_orientation: 5.0 + time_constant_position: 3.0 + egopose_interval_us: 500000 + force_gt_duration_us: 20000000 + min_traffic_duration_us: 3000000 + n_rollouts: 1 + n_sim_steps: 8 + physics_update_mode: NONE + planner_delay_us: 0 + route_generator_type: MAP + send_av_messages: false + send_recording_ground_truth: false + time_start_offset_us: 1000000