torchdrivesim.behavior.replay ============================= .. py:module:: torchdrivesim.behavior.replay Classes ------- .. autoapisummary:: torchdrivesim.behavior.replay.ReplayWrapper Functions --------- .. autoapisummary:: torchdrivesim.behavior.replay.interaction_replay Module Contents --------------- .. py:function:: interaction_replay(location, dataset_path, initial_frame=1, segment_length=40, recording=0) .. py:class:: ReplayWrapper(simulator: torchdrivesim.simulator.SimulatorInterface, npc_mask: torchdrivesim.simulator.TensorPerAgentType, agent_states: torchdrivesim.simulator.TensorPerAgentType, present_masks: torchdrivesim.simulator.TensorPerAgentType = None, time: int = 0) Bases: :py:obj:`torchdrivesim.simulator.NPCWrapper` Performs log replay for a subset of agents based on their recorded trajectories. The log has a finite length T, after which the replay will loop back from the beginning. :param simulator: existing simulator to wrap :param npc_mask: A functor of tensors with a single dimension of size A, indicating which agents to replay. The tensors can not have batch dimensions. :param agent_states: a functor of BxAxTxSt tensors with states to replay across time, which should be padded with arbitrary values for non-replay agents :param present_masks: indicates when replay agents appear and disappear; by default they're all present at all times :param time: initial index into the time dimension for replay, incremented at every step .. py:method:: _npc_teleport_to() Provides the states to which the NPCs should be set after `step`, with arbitrary padding for the remaining agents. By default, no teleportation is performed, but subclasses may use it instead of, or on top of defining the NPC action. :returns: a functor of BxAxSt tensors, where A is the number of agents in the inner simulator, or `None` if no teleportation is required .. py:method:: _update_npc_present_mask() Computes updated present masks for NPCs, with arbitrary padding for the remaining agents. By default, leaves present masks unchanged. :returns: a functor of BxA boolean tensors, where A is the number of agents in the inner simulator .. py:method:: step(action) 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:: to(device) -> typing_extensions.Self Modifies the simulator in-place, putting all tensors on the device provided. .. py:method:: copy() 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, in_place=True) 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) Picks selected elements of the batch. The input is a tensor of indices into the batch dimension. .. py:method:: validate_agent_types() .. py:method:: validate_tensor_shapes()