torchdrivesim.simulator ======================= .. py:module:: torchdrivesim.simulator Attributes ---------- .. autoapisummary:: torchdrivesim.simulator.logger Classes ------- .. autoapisummary:: torchdrivesim.simulator.CollisionMetric torchdrivesim.simulator.TorchDriveConfig torchdrivesim.simulator.SpawnController torchdrivesim.simulator.NPCController torchdrivesim.simulator.CompoundNPCController torchdrivesim.simulator.Simulator Module Contents --------------- .. py:data:: logger :value: None .. py:class:: CollisionMetric Bases: :py:obj:`enum.Enum` Method used to calculate collisions between agents. .. py:attribute:: iou :value: 'iou' .. py:attribute:: discs :value: 'discs' .. py:attribute:: nograd :value: 'nograd' .. py:attribute:: nograd_pytorch3d :value: 'nograd-pytorch3d' .. py:class:: TorchDriveConfig Top-level configuration for a TorchDriveSim simulator. .. py:attribute:: renderer :type: torchdrivesim.rendering.RendererConfig .. py:attribute:: single_agent_rendering :type: bool :value: False .. py:attribute:: collision_metric :type: CollisionMetric .. py:attribute:: offroad_threshold :type: float :value: 0.5 .. py:attribute:: left_handed_coordinates :type: bool :value: False .. py:attribute:: wrong_way_angle_threshold :type: float .. py:attribute:: lanelet_inclusion_tolerance :type: float :value: 1.0 .. py:attribute:: waypoint_removal_threshold :type: float :value: 2.0 .. py:class:: SpawnController(exit_boundary: Optional[torch.Tensor] = None, spawn_states: Optional[torch.Tensor] = None, spawn_masks: Optional[torch.Tensor] = None) Handles spawning and despawning of NPCs. If exit_boundary is provided, NPCs will be despawned if they are outside the boundary. If spawn_states and spawn_masks are provided, NPCs will be spawned at the specified states and masks if they're not already present. :param exit_boundary: Bx2xN tensor, where N is the number of vertices of the polygon. :param spawn_states: BxAxTx4 tensor, where A is the number of NPCs, T is the number of timesteps. :param spawn_masks: BxAxT boolean tensor, where A is the number of NPCs, T is the number of timesteps. .. py:attribute:: exit_boundary :value: None .. py:attribute:: spawn_states :value: None .. py:attribute:: spawn_masks :value: None .. py:attribute:: time :value: 0 .. py:method:: spawn_despawn_npcs(simulator: Simulator) -> None .. py:method:: to(device) .. py:method:: copy() .. py:method:: extend(n, in_place=True) .. py:method:: select_batch_elements(idx, in_place=True) .. py:class:: NPCController(npc_size: torch.Tensor, npc_state: torch.Tensor, npc_present_mask: Optional[torch.Tensor] = None, npc_types: Optional[torch.Tensor] = None, agent_type_names: Optional[List[str]] = None, spawn_controller: Optional[SpawnController] = None) Base class for non-playable character controllers. It leaves the state unchanged on each step. .. py:attribute:: npc_size .. py:attribute:: npc_state .. py:attribute:: npc_present_mask :value: None .. py:attribute:: npc_types :value: None .. py:attribute:: agent_type_names :value: None .. py:attribute:: spawn_controller :value: None .. py:method:: get_npc_state() .. py:method:: get_npc_size() .. py:method:: get_npc_types() .. py:method:: get_npc_present_mask() .. py:method:: spawn_despawn_npcs(simulator: Simulator) -> None .. py:method:: advance_npcs(simulator: Simulator) -> None .. py:method:: to(device) .. py:method:: copy() .. py:method:: extend(n, in_place=True) .. py:method:: select_batch_elements(idx, in_place=True) .. py:class:: CompoundNPCController(controllers: List[NPCController], controller_indices: torch.Tensor) Bases: :py:obj:`NPCController` Combines multiple NPC controllers by assigning each agent to one of the controllers. :param controllers: List of NPCController objects :param controller_indices: BxA tensor of indices into the controllers list .. py:attribute:: controllers .. py:attribute:: controller_indices .. py:method:: gather_npc_states() .. py:method:: advance_npcs(simulator: Simulator) -> None .. py:method:: to(device) .. py:method:: copy() .. py:method:: extend(n, in_place=True) .. py:method:: select_batch_elements(idx, in_place=True) .. py:class:: Simulator(road_mesh: torchdrivesim.mesh.BirdviewMesh, kinematic_model: torchdrivesim.kinematic.KinematicModel, agent_size: torch.Tensor, initial_present_mask: torch.Tensor, cfg: TorchDriveConfig, renderer: Optional[torchdrivesim.rendering.BirdviewRenderer] = None, lanelet_map: Optional[List[Optional[torchdrivesim.lanelet2.LaneletMap]]] = None, recenter_offset: Optional[torch.Tensor] = None, birdview_mesh_generator: Optional[torchdrivesim.mesh.BirdviewRGBMeshGenerator] = None, internal_time: int = 0, traffic_controls: Optional[Dict[str, torchdrivesim.traffic_controls.BaseTrafficControl]] = None, waypoint_goals: Optional[torchdrivesim.goals.WaypointGoal] = None, agent_types: Optional[torch.Tensor] = None, agent_type_names: Optional[List[str]] = None, npc_controller: Optional[NPCController] = None, agent_lr: Optional[torch.Tensor] = None, lane_features: Optional[torchdrivesim.lanelet2.LaneFeatures] = None, observation_noise_model: Optional[torchdrivesim.observation_noise.ObservationNoise] = None, action_model_extras: Optional[Dict[str, Any]] = None) :param road_mesh: a mesh indicating the driveable area :param kinematic_model: determines the action space, constraints, and the initial state of all agents :param agent_size: a functor of Bx2 tensors indicating agent length and width :param initial_present_mask: a functor of BxA tensors indicating which agents are initially present and not padding :param cfg: holds various configuration options :param renderer: specify if using a non-standard renderer or static meshes beyond the road mesh (default from config) :param lanelet_map: provide the map to compute orientation losses, one map per batch element where available :param recenter_offset: if the coordinate system from lanelet_map was shifted, this value will be used to shift it back :param internal_time: initial value for step counter :param traffic_controls: applicable traffic controls by type :param waypoint_goals: waypoints for each agent :param agent_types: a tensor of BxA long tensors indicating the agent type index for each agent :param agent_type_names: a list of agent type names to index into .. py:attribute:: road_mesh .. py:attribute:: lanelet_map :value: None .. py:attribute:: recenter_offset :value: None .. py:attribute:: kinematic_model .. py:attribute:: agent_size .. py:attribute:: present_mask .. py:attribute:: action_model_extras :value: None .. py:attribute:: _agent_types :value: None .. py:attribute:: _batch_size .. py:attribute:: agent_type :value: None .. py:attribute:: agent_lr :value: None .. py:attribute:: lane_features :value: None .. py:attribute:: npc_controller :value: None .. py:attribute:: cfg :type: TorchDriveConfig .. py:attribute:: traffic_controls :value: None .. py:attribute:: waypoint_goals :value: None .. py:attribute:: warned_no_lanelet :value: False .. py:attribute:: internal_time :value: 0 .. py:property:: agent_types :type: Optional[List[str]] List of agent types used by this simulator, or `None` if only one type used. .. py:property:: action_size :type: int Defines the size of the action space for each agent type. .. py:property:: batch_size :type: int .. py:method:: to(device) -> typing_extensions.Self Modifies the simulator in-place, putting all tensors on the device provided. .. py:method:: copy() -> typing_extensions.Self Duplicates this simulator, allowing for independent subsequent execution. The copy is relatively shallow, in that the tensors are the same objects but dictionaries referring to them are shallowly copied. .. py:method:: extend(n: int, in_place: bool = True) -> typing_extensions.Self Multiplies the first batch dimension by the given number. Like in pytorch3d, this is equivalent to introducing extra batch dimension on the right and then flattening. .. py:method:: select_batch_elements(idx, in_place=True) -> typing_extensions.Self Picks selected elements of the batch. The input is a tensor of indices into the batch dimension. .. py:method:: __getitem__(item: torch.Tensor) -> typing_extensions.Self Allows indexing syntax. `item` should be an iterable collection of indices. .. py:property:: agent_count :type: int How many agents of each type are there in the simulation. This counts the available slots, not taking present masks into consideration. .. py:property:: npc_count :type: int How many non-playable characters are there in the simulation. .. py:method:: validate_agent_types() .. py:method:: validate_tensor_shapes() .. py:method:: get_action_model_extras() -> Dict[str, Any] Returns any extra information to be passed to the action model .. py:method:: get_world_center() -> torch.Tensor Returns a Bx2 tensor with the coordinates of the map center. .. py:method:: get_state() -> torch.Tensor Returns a functor of BxAxSt tensors representing current agent states. .. py:method:: get_waypoints(count: int = 1) -> torch.Tensor Returns a functor of BxAxcount*Mx2 tensors representing current agent waypoints. .. py:method:: get_waypoints_state() -> torch.Tensor Returns a functor of BxAx1 tensors representing current agent waypoints state. .. py:method:: get_waypoints_mask(count: int = 1) -> torch.Tensor Returns a functor of BxAxcount*M boolean tensors representing current agent waypoints present mask. .. py:method:: compute_wrong_way() -> torch.Tensor Wrong-way metric for each agent, based on the inner product between the agent and lane direction. See `torchdrivesim.infractions.lanelet_orientation_loss` for details. :returns: a functor of BxA tensors .. py:method:: get_agent_size() -> torch.Tensor Returns a functor of BxAx2 tensors representing agent length and width. .. py:method:: get_agent_type() -> torch.Tensor Returns a functor of BxA long tensors containing agent type indexes relative to the list containing all agent types as returned by `Simulator.agent_types`. .. py:method:: get_agent_type_names() -> List[str] Returns a list of all agent types used in the simulation. .. py:method:: get_agent_lr() -> torch.Tensor Returns a functor of BxA long tensors containing the rear offset .. py:method:: get_present_mask() -> torch.Tensor Returns a functor of BxA boolean tensors indicating which agents are currently present in the simulation. .. py:method:: get_noisy_state() -> torch.Tensor Returns a functor of BxAx(A+Npc)xSt tensors representing current agent states. .. py:method:: get_noisy_agent_size() -> torch.Tensor Returns a functor of BxAx(A+Npc)x2 tensors representing agent length and width. .. py:method:: get_noisy_present_mask() -> torch.Tensor Returns a functor of BxAx(A+Npc) boolean tensors indicating which agents are currently present in the simulation. .. py:method:: get_npc_state() -> torch.Tensor Returns a functor of BxNpcxSt tensors representing current non-playable character states. .. py:method:: get_npc_size() -> torch.Tensor Returns a functor of BxNpcx2 tensors representing non-playable character length and width. .. py:method:: get_npc_present_mask() -> torch.Tensor Returns a functor of BxNpc boolean tensors indicating which non-playable characters are currently present in the simulation. .. py:method:: get_npc_types() -> torch.Tensor Returns a functor of BxNpc long tensors containing non-playable character type indexes relative to the list containing all agent types as returned by `Simulator.agent_types`. .. py:method:: get_all_agent_state() -> torch.Tensor Returns a functor of Bx(A+Npc)x4 tensors, where the last dimension contains the following information: x, y, psi, v. .. py:method:: get_all_agent_size() -> torch.Tensor Returns a functor of Bx(A+Npc)x2 tensors, where the last dimension contains the following information: length, width. .. py:method:: get_all_agent_present_mask() -> torch.Tensor Returns a functor of Bx(A+Npc) boolean tensors, indicating which agents are currently present in the simulation. .. py:method:: get_all_agent_type() -> torch.Tensor Returns a functor of Bx(A+Npc) long tensors, indicating the agent type index for each agent. .. py:method:: get_all_agents_absolute() -> torch.Tensor Returns a functor of Bx(A+Npc)x6 tensors, where the last dimension contains the following information: x, y, psi, length, width, present. Typically used to implement non-visual observation modalities. .. py:method:: get_noisy_all_agents_absolute() -> torch.Tensor Returns a functor of BxAx(A+Npc)x6 tensors, where the last dimension contains the following information: x, y, psi, length, width, present. Typically used to implement non-visual observation modalities. .. py:method:: get_all_agents_relative(exclude_self: bool = True) -> torch.Tensor Returns a functor of BxAx(A+Npc)x6 tensors, specifying for each of A agents the relative position about the other agents. 'All' is the number of all agents in the simulation, including hidden ones, across all agent types. If `exclude_self` is set, for each agent in A, that agent itself is removed from All. The final dimension has the same meaning as in `get_all_agents_absolute`, except now the positions and orientations are relative to the specified agent. .. py:method:: get_noisy_all_agents_relative(exclude_self: bool = True) -> torch.Tensor Returns a functor of BxAx(A+Npc)x6 tensors, specifying for each of A agents the relative position about the other agents. 'All' is the number of all agents in the simulation, including hidden ones, across all agent types. If `exclude_self` is set, for each agent in A, that agent itself is removed from All. The final dimension has the same meaning as in `get_noisy_all_agents_absolute`, except now the positions and orientations are relative to the specified agent. .. py:method:: get_traffic_controls() -> Dict[str, torchdrivesim.traffic_controls.BaseTrafficControl] Produces all traffic controls existing in the simulation, grouped by type. .. py:method:: get_noisy_lane_features() -> torchdrivesim.lanelet2.LaneFeatures .. py:method:: get_noisy_road_mesh() .. py:method:: get_noisy_background_mesh() -> torchdrivesim.lanelet2.LaneFeatures .. py:method:: get_noisy_traffic_controls() -> Dict[str, torchdrivesim.traffic_controls.BaseTrafficControl] .. py:method:: step(agent_action: torch.Tensor) -> None Runs the simulation for one step with given agent actions. Input is a functor of BxAxAc tensors, where Ac is determined by the kinematic model. .. py:method:: set_state(agent_state: torch.Tensor, mask: Optional[torch.Tensor] = None) -> None Arbitrarily set the state of the agents, without advancing the simulation. The change is effective immediately, without waiting for the next step. :param agent_state: a functor of BxAx4 tensors with agent states :param mask: a functor of BxA boolean tensors, deciding which agent states to update; all by default .. py:method:: update_present_mask(present_mask: torch.Tensor) -> None Sets the present mask of agents to the provided value. :param present_mask: a functor of BxA boolean tensors .. py:method:: fit_action(future_state: torch.Tensor, current_state: Optional[torch.Tensor] = None) -> torch.Tensor Computes an action that would (aproximately) produce the desired state. :param future_state: a functor of BxAx4 tensors defining the desired state :param current_state: if different from the current simulation state, in the same format as future state :returns: a functor of BxAxAc tensors .. py:method:: render(camera_xy: torch.Tensor, camera_psi: torch.Tensor, res: Optional[torchdrivesim.utils.Resolution] = None, rendering_mask: Optional[torch.Tensor] = None, fov: Optional[float] = None, waypoints: Optional[torch.Tensor] = None, waypoints_rendering_mask: Optional[torch.Tensor] = None, custom_agent_colors: Optional[torch.Tensor] = None, noisy_perception: bool = False) -> torch.Tensor Renders the world from bird's eye view using cameras in given positions. :param camera_xy: BxNx2 tensor of x-y positions for N cameras :param camera_psi: BxNx1 tensor of orientations for N cameras :param res: desired image resolution (only square resolutions are supported; by default use value from config) :param rendering_mask: functor of BxNxAll tensors, indicating which agents should be rendered each camera :param fov: the field of view of the resulting image in meters (by default use value from config) :param waypoints: BxNxMx2 tensor of `M` waypoints per camera (x,y) :param waypoints_rendering_mask: BxNxM tensor of `M` waypoint masks per camera, indicating which waypoints should be rendered :param custom_agent_colors: BxNxAllx3 RGB tensor defining the color of each agent to each camera :returns: BxNxCxHxW tensor of resulting RGB images for each camera .. py:method:: render_egocentric(ego_rotate: bool = True, res: Optional[torchdrivesim.utils.Resolution] = None, fov: Optional[float] = None, visibility_matrix: Optional[torch.Tensor] = None, custom_agent_colors: Optional[torch.Tensor] = None, n_subsequent_waypoints: int = 1, noisy_perception: bool = False) -> torch.Tensor Renders the world using cameras placed on each agent. :param ego_rotate: whether to orient the cameras such that the ego agent faces up in the image :param res: desired image resolution (only square resolutions are supported; by default use value from config) :param fov: the field of view of the resulting image in meters (by default use value from config) :param visibility_matrix: a BxAxAll boolean tensor indicating which agents can see each other :param custom_agent_colors: a BxAxAllx3 RGB tensor specifying what colors agent see each other as :param n_subsequent_waypoints: the number of subsequent waypoints to render :returns: a functor of BxAxCxHxW tensors of resulting RGB images for each agent. .. py:method:: compute_offroad() -> torch.Tensor Offroad metric for each agent, defined as the distance to the road mesh. See `torchdrivesim.infractions.offroad_infraction_loss` for details. :returns: a functor of BxA tensors .. py:method:: compute_traffic_lights_violations() -> torch.Tensor Boolean value indicating whether each agent is committing a traffic light violation. See `torchdrivesim.infractions.traffic_controls.TrafficLightControl.compute_violations` for details. :returns: a functor of BxA tensors .. py:method:: _compute_collision_of_single_agent(box: torch.Tensor, remove_self_overlap: Optional[torch.Tensor] = None, agent_types: Optional[List[str]] = None) -> torch.Tensor Computes the collision metric for an agent specified as a bounding box. Includes collisions with all agents in the simulation, including the ones not exposed through the interface of this class. Used with `discs` and `iou` metrics. :param box: Bx5 tensor, with the last dimension being (x,y,length,width,psi). :param remove_self_overlap: B boolean tensor, where if the input agent is present in the simulation, set this to subtract self-overlap. By default it is assumed that self overlapping exists and will be removed. :param agent_types: An optional list of specific agent types for computing collisions with. By default all available agent types will be used. :returns: a tensor with a single dimension of B elements .. py:method:: _compute_collision_of_multi_agents(mask: Optional[torch.Tensor] = None) -> torch.Tensor Computes the collision metric for selected (default all) agents in the simulation. Includes collisions with all agents in the simulation, including the ones not exposed through the interface of this class. Used with `nograd` and `nograd-pytorch3d` metrics. :param mask: a functor of BxA boolean tensors, indicating for which agents to compute the loss (by default use present mask) :returns: a functor of BxA tensors .. py:method:: compute_collision(agent_types: Optional[List[str]] = None) -> torch.Tensor Compute the collision metric for agents exposed through the interface of this class. Includes collisions with agents not exposed through the interface. Collisions are defined as overlap of agents' bounding boxes, with details determined by the specific method chosen in the config. :param agent_types: An optional list of specific agent types for computing collisions with. Not supported by the collision metrics `nograd` and `nograd-pytorch3d`. :returns: a BxA tensor