torchdrivesim.lanelet2 ====================== .. py:module:: torchdrivesim.lanelet2 .. autoapi-nested-parse:: All utilities for working with maps in Lanelet2 format. This module imports correctly and exports all the usual signatures even when the lanelet2 package is not installed, but in that case all calls to its functions raise the Lanelet2NotFound exception. Attributes ---------- .. autoapisummary:: torchdrivesim.lanelet2.is_available Exceptions ---------- .. autoapisummary:: torchdrivesim.lanelet2.Lanelet2NotFound torchdrivesim.lanelet2.LaneletError Classes ------- .. autoapisummary:: torchdrivesim.lanelet2.LaneFeatures Functions --------- .. autoapisummary:: torchdrivesim.lanelet2.load_lanelet_map torchdrivesim.lanelet2.find_lanelet_directions torchdrivesim.lanelet2.find_direction torchdrivesim.lanelet2.pick_random_point_and_orientation torchdrivesim.lanelet2.road_mesh_from_lanelet_map torchdrivesim.lanelet2.line_segments_to_mesh torchdrivesim.lanelet2.lanelet_map_to_lane_mesh Module Contents --------------- .. py:data:: is_available :value: True .. py:class:: LaneFeatures .. py:attribute:: dense_lane_features :type: Optional[torch.Tensor] :value: None .. py:attribute:: dense_lane_features_mask :type: Optional[torch.Tensor] :value: None .. py:attribute:: sparse_lane_features :type: Optional[torch.Tensor] :value: None .. py:attribute:: sparse_lane_features_mask :type: Optional[torch.Tensor] :value: None .. py:method:: to(device) -> typing_extensions.Self .. py:method:: copy() -> typing_extensions.Self .. py:method:: extend(n: int) -> typing_extensions.Self .. py:method:: select_batch_elements(idx) -> typing_extensions.Self .. py:exception:: Lanelet2NotFound Bases: :py:obj:`ImportError` Python bindings for Lanelet2 are not installed. .. py:exception:: LaneletError Bases: :py:obj:`RuntimeError` Some function related to Lanelet2 failed. .. py:function:: load_lanelet_map(map_path: str, origin: Tuple[float, float] = (0, 0)) -> LaneletMap Load a Lanelet2 map from an OSM file on disk. :param map_path: local path to OSM file containing the map :param origin: latitude and longitude of the origin to use with UTM projector :raises Lanelet2NotFound: if lanelet2 package is not available :raises FileNotFoundError: if specified file doesn't exist .. py:function:: find_lanelet_directions(lanelet_map: LaneletMap, x: float, y: float, tags_to_exclude: Optional[List[str]] = None, lanelet_dist_tolerance: float = 1.0) -> List[float] For a given point, find local orientations of all lanelets that contain it. :param lanelet_map: the map with a lanelet layer :param x: first coordinate of the point in the map's coordinate frame :param y: second coordinate of the point in the map's coordinate frame :param tags_to_exclude: lanelets tagged with any of those tags will be omitted as if they didn't exist :param lanelet_dist_tolerance: how far out of a lanelet a car can be for the lanelet to still be containing it :returns: for each lanelet, the angle representing its local orientation in radians :raises Lanelet2NotFound: if lanelet2 package is not available .. py:function:: find_direction(linestring, location3d) -> float For a given linestring and a point near it, finds the local orientation of the linestring. :returns: the linestring's local orientation in radians :raises Lanelet2NotFound: if lanelet2 package is not available :raises LaneletError: when the method fails, usually because the linestring has a weird shape .. py:function:: pick_random_point_and_orientation(lanelet_map: LaneletMap) -> Tuple[float, float, float] Picks a point on the map by randomly selecting a lanelet and then randomly selecting a point along its centerline, both using `random` package. :returns: tuple (x, y, orientation), using the map's coordinate frame and radians :raises Lanelet2NotFound: if lanelet2 package is not available .. py:function:: road_mesh_from_lanelet_map(lanelet_map: LaneletMap, lanelets: Optional[List[int]] = None) -> torchdrivesim.mesh.BaseMesh Creates a road mesh by triangulating all lanelets in a given map. :param lanelet_map: map to triangulate :param lanelets: if specified, only use lanelets with those ids .. py:function:: line_segments_to_mesh(points: torch.Tensor, line_width: float = 0.3, eps: float = 1e-06) -> torchdrivesim.mesh.BaseMesh Converts a given collection of line segments to a mesh visualizing them. :param points: BxNx2x2 tensor specifying N line segments, each consisting of a pair of points :param line_width: width of the line in meters :param eps: small value to add for avoiding division by zero :returns: mesh visualizing the line, with 6*N verts and 4*N faces .. py:function:: lanelet_map_to_lane_mesh(lanelet_map: LaneletMap, left_handed: bool = False, batch_size: int = 50000, left_right_marking_join_threshold: float = 0.1, lanelets: Optional[List[int]] = None, lane_boundary_width: float = 0.275) -> torchdrivesim.mesh.BirdviewMesh Creates a lane marking mesh from a given map. :param lanelet_map: map to use :param left_handed: whether the map's coordinate system is left-handed (flips the left and right boundary designations) :param batch_size: controls the amount of points processed in parallel :param left_right_marking_join_threshold: if left and right markings are this close, they will be treated as joint :param lane_boundary_width: in meters, the thickness of the lane markings