torchdrivesim.infractions
#
Module Contents#
Functions#
|
Computes the distance between a pointcloud and a mesh, defined as the L2 distance |
|
Calculates off-road infraction loss, defined as the sum of thresholded distances |
|
Calculate a loss value of the agent orientation regarding to the direction of the lanelet segment. |
|
Computes an approximate, differentiable IoU between two oriented bounding boxes. |
|
Computes the number of collisions per agent in batch. |
|
Returns the number of collisions per agent in a batch. |
|
Converts a bounding box to the specified number of equally spaced discs with radius half the width. |
|
Calculates an upper triangular matrix of size equal to the number of rotated rectangles which |
|
Calculate the 4 corners of the rotated rectangles given the center point, the size and the orientation. |
|
Calculate the differentiable collision loss as described in the paper TrafficSim. |
Attributes#
- torchdrivesim.infractions.point_mesh_face_distance(meshes: pytorch3d.structures.Meshes, pcls: pytorch3d.structures.Pointclouds, reduction: str = 'sum', weighted: bool = False, threshold: float = 0) torch.Tensor [source]#
Computes the distance between a pointcloud and a mesh, defined as the L2 distance from each point to the closest face in the mesh, reduced across the points in the cloud. Runs in batch mode for both mesh and pointcloud.
- Parameters:
meshes – a batch of B meshes
pcls – a batch of B pointcouds
reduction – ‘none’ | ‘sum’ | ‘mean’ | ‘min’ | ‘max’
weighted – weight by the inverse of number of points in the pointcloud
threshold – reduce result by this amount and clip at zero from below
- Returns:
BxP tensor if reduction is ‘none’, else Bx1 tensor
- torchdrivesim.infractions.offroad_infraction_loss(agent_states: torch.Tensor, lenwid: torch.Tensor, driving_surface_mesh: pytorch3d.structures.Meshes | torchdrivesim.mesh.BaseMesh, threshold: float = 0) torch.Tensor [source]#
Calculates off-road infraction loss, defined as the sum of thresholded distances from agent corners to the driving surface mesh.
- Parameters:
agent_states – BxAx4 tensor of agent states x,y,orientation,speed
lenwid – BxAx2 tensor providing length and width of each agent
driving_surface_mesh – a batch of B meshes defining driving surface
threshold – if given, the distance of each corner is thresholded using this value
- Returns:
BxA tensor of offroad losses for each agent
- torchdrivesim.infractions.lanelet_orientation_loss(lanelet_maps: List[torchdrivesim.lanelet2.LaneletMap | None], agents_state: torch.Tensor, recenter_offset: torch.Tensor | None = None) torch.Tensor [source]#
Calculate a loss value of the agent orientation regarding to the direction of the lanelet segment. The loss is computed by finding the direction of the lanelet the agent is currently on, and then taking max(0, -cos(δ)) given δ is the orientation difference between the lanelet orientation and the agent orientation. This normalizes the loss range from 0-1 while ignoring the angle difference less than 90 degrees. In case it is ambiguous which lanelet the agent is on, the one best matching agent orientation is on.
- Parameters:
lanelet_maps – a list of B maps; None is means orientation loss won’t be computed for that batch element
agents_state – BxAx4 tensor of agent states x,t,orientation,speed
recenter_offset – Bx2 tensor that needs to be added to agent coordinates to match them to map
- Returns:
BxA tensor of orientation losses for all agents
- torchdrivesim.infractions.iou_differentiable(box1: torch.Tensor, box2: torch.Tensor, fast: bool = True) torch.Tensor [source]#
Computes an approximate, differentiable IoU between two oriented bounding boxes. Accepts multiple batch dimensions.
- Parameters:
box1 – Bx5 tensor x,y,length,width,orientation
box2 – Bx5 tensor
fast – whether to use faster but less accurate method
- Returns:
tensor of shape (B,) with IoU values
- torchdrivesim.infractions.compute_agent_collisions_metric_pytorch3d(all_rects: torch.Tensor, masks: torch.Tensor) torch.Tensor [source]#
Computes the number of collisions per agent in batch.
- Parameters:
all_rects – BxAx5 tensor of oriented rectangles x,y,length,width,orientation
masks – BxA boolean tensor, indicating whether to compute collisions for this agent
- Returns:
BxA tensor with collision counts per agent
- torchdrivesim.infractions.compute_agent_collisions_metric(all_rects: numpy.ndarray, collision_masks: numpy.ndarray, present_masks: numpy.ndarray) numpy.ndarray [source]#
Returns the number of collisions per agent in a batch.
- Parameters:
all_rects – BxAx5 array of oriented rectangles x,y,length,width,orientation
collision_masks – BxA boolean array, indicating whether to compute collisions for this agent
present_masks – BxA boolean array, indicating which rectangles are not padding
- Returns:
BxA array with collision counts per agent
- torchdrivesim.infractions.bbox2discs(box: torch.Tensor, num_discs: int = 5, backend: str = 'torch') Tuple[torch.Tensor, torch.Tensor] [source]#
Converts a bounding box to the specified number of equally spaced discs with radius half the width. B is the batch size. A bounding box is described by 5 values in this order: (x, y, length, width, orientation).) :param box: Bx5 tensor or bounding boxes :param num_discs: The number of discs used to represent a vehicle. Must be a positive odd number. (default: 5) :param backend: Either torch or numpy. (default: ‘torch’)
- Returns:
A tuple (agent_disc_center, agent_r) where agent_disc_center is the coordinates of the center of each disc (B, num_discs, 2) and agent_r is the radius of the discs (B, 1)
- torchdrivesim.infractions.get_all_intersections(rects: numpy.ndarray, ego_idx: int | None = None) numpy.ndarray [source]#
Calculates an upper triangular matrix of size equal to the number of rotated rectangles which indicating whether one rectangle intersects with another. :param rects: (agents_count x 5) numpy array :param ego_idx: Optional ego index for ego only mode
- Returns:
An upper triangular matrix of size equal to the number of rotated rectangles
- torchdrivesim.infractions.rectangle_vertices(cx: numpy.ndarray, cy: numpy.ndarray, w: numpy.ndarray, h: numpy.ndarray, angle: numpy.ndarray) numpy.ndarray [source]#
Calculate the 4 corners of the rotated rectangles given the center point, the size and the orientation. :param cx: Bx1 array with x coordinate of the center point :param cy: Bx1 array with y coordinate of the center point :param w: Bx1 array with width of the rectangle :param h: Bx1 array with height of the rectangle :param angle: Bx1 array with yaw angle of the rectangle
- Returns:
Bx4 corners of the rectangle
- torchdrivesim.infractions.collision_detection_with_discs(box1: torch.Tensor, box2: torch.Tensor, num_discs: int = 5, backend: str = 'torch')[source]#
Calculate the differentiable collision loss as described in the paper TrafficSim. Accepts multiple batch dimensions. A bounding box is described by 5 values in this order: (x, y, length, width, orientation)
- Parameters:
box1 – Bx5 tensor
box2 – Bx5 tensor
num_discs – The number of discs used to represent a vehicle. Must be a positive odd number.
backend – Either torch or numpy.
- Returns:
tensor of shape (B,) with collision values between corresponding agents