diff --git a/README.md b/README.md index 2710f336..b8321666 100644 --- a/README.md +++ b/README.md @@ -14,11 +14,13 @@ Welcome to the devkit of the [nuScenes](https://www.nuscenes.org/nuscenes) and [ - [Prediction challenge](#prediction-challenge) - [CAN bus expansion](#can-bus-expansion) - [Map expansion](#map-expansion) + - [Map versions](#map-versions) - [Getting started with nuScenes](#getting-started-with-nuscenes) - [Known issues](#known-issues) - [Citation](#citation) ## Changelog +- Nov. 23, 2020: Devkit v1.1.2: Release map-expansion v1.3 with lidar basemap. - Nov. 9, 2020: Devkit v1.1.1: Lidarseg evaluation code, NeurIPS challenge announcement. - Aug. 31, 2020: Devkit v1.1.0: nuImages v1.0 and nuScenes-lidarseg v1.0 code release. - Jul. 7, 2020: Devkit v1.0.9: Misc updates on map and prediction code. @@ -125,10 +127,19 @@ To install this expansion, please follow these steps: In July 2019 we published a map expansion with 11 semantic layers (crosswalk, sidewalk, traffic lights, stop lines, lanes, etc.). To install this expansion, please follow these steps: - Download the expansion from the [Download page](https://www.nuscenes.org/download), -- Extract the .json files to your nuScenes `maps` folder. +- Extract the contents (folders `basemap`, `expansion` and `prediction`) to your nuScenes `maps` folder. - Get the latest version of the nuscenes-devkit. - If you already have a previous version of the devkit, update the pip requirements (see [details](https://github.com/nutonomy/nuscenes-devkit/blob/master/docs/installation.md)): `pip install -r setup/requirements.txt` - Get started with the [map expansion tutorial](https://github.com/nutonomy/nuscenes-devkit/blob/master/python-sdk/tutorials/map_expansion_tutorial.ipynb). +For more information, see the [map versions](#map-versions) below. + +### Map versions +Here we give a brief overview of the different map versions: +- **v1.3**: Add BitMap class that supports new lidar basemap and legacy semantic prior map. Remove [one broken lane](https://github.com/nutonomy/nuscenes-devkit/issues/493). +- **v1.2**: Expand devkit and maps to include arcline paths and lane connectivity for the prediction challenge. +- **v1.1**: Resolved issues with ego poses being off the drivable surface. +- **v1.0**: Initial map expansion release from July 2019. Supports 11 semantic layers. +- **nuScenes v1.0**: Came with a bitmap for the semantic prior. All code is contained in nuscenes.py. ### Getting started with nuScenes Please follow these steps to make yourself familiar with the nuScenes dataset: @@ -155,6 +166,7 @@ However, some minor issues remain: - For *singapore-hollandvillage* and *singapore-queenstown* the traffic light 3d poses are all 0 (except for tz). - For *boston-seaport*, the ego poses of 3 scenes (499, 515, 517) are slightly incorrect and 2 scenes (501, 502) are outside the annotated area. - For *singapore-onenorth*, the ego poses of about 10 scenes were off the drivable surface. This has been **resolved in map v1.1**. +- Some lanes are disconnected from the rest of the lanes. We chose to keep these as they still provide valuable information. **Annotations**: - A small number of 3d bounding boxes is annotated despite the object being temporarily occluded. For this reason we make sure to **filter objects without lidar or radar points** in the nuScenes benchmarks. See [issue 366](https://github.com/nutonomy/nuscenes-devkit/issues/366). diff --git a/python-sdk/nuscenes/eval/detection/data_classes.py b/python-sdk/nuscenes/eval/detection/data_classes.py index a4e02a6e..8e0a7fcc 100644 --- a/python-sdk/nuscenes/eval/detection/data_classes.py +++ b/python-sdk/nuscenes/eval/detection/data_classes.py @@ -21,7 +21,7 @@ def __init__(self, dist_th_tp: float, min_recall: float, min_precision: float, - max_boxes_per_sample: float, + max_boxes_per_sample: int, mean_ap_weight: int): assert set(class_range.keys()) == set(DETECTION_NAMES), "Class count mismatch." diff --git a/python-sdk/nuscenes/eval/prediction/baseline_model_inference.py b/python-sdk/nuscenes/eval/prediction/baseline_model_inference.py index cba4741a..cd881ac0 100644 --- a/python-sdk/nuscenes/eval/prediction/baseline_model_inference.py +++ b/python-sdk/nuscenes/eval/prediction/baseline_model_inference.py @@ -18,7 +18,7 @@ def main(version: str, data_root: str, split_name: str, output_dir: str, config_name: str = 'predict_2020_icra.json') -> None: """ Performs inference for all of the baseline models defined in the physics model module. - :param version: nuScenes data set version. + :param version: nuScenes dataset version. :param data_root: Directory where the NuScenes data is stored. :param split_name: nuScenes data split name, e.g. train, val, mini_train, etc. :param output_dir: Directory where predictions should be stored. diff --git a/python-sdk/nuscenes/eval/prediction/compute_metrics.py b/python-sdk/nuscenes/eval/prediction/compute_metrics.py index 51ccb447..f3d201a7 100644 --- a/python-sdk/nuscenes/eval/prediction/compute_metrics.py +++ b/python-sdk/nuscenes/eval/prediction/compute_metrics.py @@ -44,7 +44,7 @@ def main(version: str, data_root: str, submission_path: str, """ Computes metrics for a submission stored in submission_path with a given submission_name with the metrics specified by the config_name. - :param version: nuScenes data set version. + :param version: nuScenes dataset version. :param data_root: Directory storing NuScenes data. :param submission_path: Directory storing submission. :param config_name: Name of config file. diff --git a/python-sdk/nuscenes/eval/prediction/metrics.py b/python-sdk/nuscenes/eval/prediction/metrics.py index 6f514a3e..aac4ffaa 100644 --- a/python-sdk/nuscenes/eval/prediction/metrics.py +++ b/python-sdk/nuscenes/eval/prediction/metrics.py @@ -207,7 +207,7 @@ def __init__(self, k_to_report: List[int], aggregators: List[Aggregator]): """ Computes the minimum average displacement error over the top k predictions. :param k_to_report: Will report the top k result for the k in this list. - :param aggregators: How to aggregate the results across the data set. + :param aggregators: How to aggregate the results across the dataset. """ super().__init__() self.k_to_report = k_to_report @@ -242,7 +242,7 @@ def __init__(self, k_to_report, aggregators: List[Aggregator]): """ Computes the minimum final displacement error over the top k predictions. :param k_to_report: Will report the top k result for the k in this list. - :param aggregators: How to aggregate the results across the data set. + :param aggregators: How to aggregate the results across the dataset. """ super().__init__() self.k_to_report = k_to_report @@ -279,7 +279,7 @@ def __init__(self, k_to_report: List[int], aggregators: List[Aggregator], If any point in the prediction is more than tolerance meters from the ground truth, it is a miss. This metric computes the fraction of predictions that are misses over the top k most likely predictions. :param k_to_report: Will report the top k result for the k in this list. - :param aggregators: How to aggregate the results across the data set. + :param aggregators: How to aggregate the results across the dataset. :param tolerance: Threshold to consider if a prediction is a hit or not. """ self.k_to_report = k_to_report @@ -318,7 +318,7 @@ def __init__(self, helper: PredictHelper, aggregators: List[Aggregator]): The OffRoadRate is defined as the fraction of trajectories that are not entirely contained in the drivable area of the map. :param helper: Instance of PredictHelper. Used to determine the map version for each prediction. - :param aggregators: How to aggregate the results across the data set. + :param aggregators: How to aggregate the results across the dataset. """ self._aggregators = aggregators self.helper = helper diff --git a/python-sdk/nuscenes/eval/prediction/splits.py b/python-sdk/nuscenes/eval/prediction/splits.py index d0090095..08a8008c 100644 --- a/python-sdk/nuscenes/eval/prediction/splits.py +++ b/python-sdk/nuscenes/eval/prediction/splits.py @@ -15,7 +15,7 @@ def get_prediction_challenge_split(split: str, dataroot: str = '/data/sets/nusce """ Gets a list of {instance_token}_{sample_token} strings for each split. :param split: One of 'mini_train', 'mini_val', 'train', 'val'. - :param dataroot: Path to the nuScenes data set. + :param dataroot: Path to the nuScenes dataset. :return: List of tokens belonging to the split. Format {instance_token}_{sample_token}. """ if split not in {'mini_train', 'mini_val', 'train', 'train_val', 'val'}: @@ -26,7 +26,7 @@ def get_prediction_challenge_split(split: str, dataroot: str = '/data/sets/nusce else: split_name = split - path_to_file = os.path.join(dataroot, "maps", "prediction_scenes.json") + path_to_file = os.path.join(dataroot, "maps", "prediction", "prediction_scenes.json") prediction_scenes = json.load(open(path_to_file, "r")) scenes = create_splits_scenes() scenes_for_split = scenes[split_name] diff --git a/python-sdk/nuscenes/map_expansion/bitmap.py b/python-sdk/nuscenes/map_expansion/bitmap.py new file mode 100644 index 00000000..7e9f2285 --- /dev/null +++ b/python-sdk/nuscenes/map_expansion/bitmap.py @@ -0,0 +1,75 @@ +import os +from typing import Tuple, Any + +import numpy as np +from PIL import Image +import matplotlib.pyplot as plt + +Axis = Any + + +class BitMap: + + def __init__(self, dataroot: str, map_name: str, layer_name: str): + """ + This class is used to render bitmap map layers. Currently these are: + - semantic_prior: The semantic prior (driveable surface and sidewalks) mask from nuScenes 1.0. + - basemap: The HD lidar basemap used for localization and as general context. + + :param dataroot: Path of the nuScenes dataset. + :param map_name: Which map out of `singapore-onenorth`, `singepore-hollandvillage`, `singapore-queenstown` and + 'boston-seaport'. + :param layer_name: The type of bitmap map, `semanitc_prior` or `basemap. + """ + self.dataroot = dataroot + self.map_name = map_name + self.layer_name = layer_name + + self.image = self.load_bitmap() + + def load_bitmap(self) -> np.ndarray: + """ + Load the specified bitmap. + """ + # Load bitmap. + if self.layer_name == 'basemap': + map_path = os.path.join(self.dataroot, 'maps', 'basemap', self.map_name + '.png') + elif self.layer_name == 'semantic_prior': + map_hashes = { + 'singapore-onenorth': '53992ee3023e5494b90c316c183be829', + 'singapore-hollandvillage': '37819e65e09e5547b8a3ceaefba56bb2', + 'singapore-queenstown': '93406b464a165eaba6d9de76ca09f5da', + 'boston-seaport': '36092f0b03a857c6a3403e25b4b7aab3' + } + map_hash = map_hashes[self.map_name] + map_path = os.path.join(self.dataroot, 'maps', map_hash + '.png') + else: + raise Exception('Error: Invalid bitmap layer: %s' % self.layer_name) + + # Convert to numpy. + if os.path.exists(map_path): + image = np.array(Image.open(map_path)) + else: + raise Exception('Error: Cannot find %s %s! Please make sure that the map is correctly installed.' + % (self.layer_name, map_path)) + + # Invert semantic prior colors. + if self.layer_name == 'semantic_prior': + image = image.max() - image + + return image + + def render(self, canvas_edge: Tuple[float, float], ax: Axis = None): + """ + Render the bitmap. + Note: Regardless of the image dimensions, the image will be rendered to occupy the entire map. + :param canvas_edge: The dimension of the current map in meters (width, height). + :param ax: Optional axis to render to. + """ + if ax is None: + ax = plt.subplot() + x, y = canvas_edge + if len(self.image.shape) == 2: + ax.imshow(self.image, extent=[0, x, 0, y], cmap='gray') + else: + ax.imshow(self.image, extent=[0, x, 0, y]) diff --git a/python-sdk/nuscenes/map_expansion/map_api.py b/python-sdk/nuscenes/map_expansion/map_api.py index 5bf887a0..53a14a0c 100644 --- a/python-sdk/nuscenes/map_expansion/map_api.py +++ b/python-sdk/nuscenes/map_expansion/map_api.py @@ -23,9 +23,10 @@ from shapely.geometry import Polygon, MultiPolygon, LineString, Point, box from tqdm import tqdm +from nuscenes.map_expansion.arcline_path_utils import discretize_lane, ArcLinePath +from nuscenes.map_expansion.bitmap import BitMap from nuscenes.nuscenes import NuScenes from nuscenes.utils.geometry_utils import view_points -from nuscenes.map_expansion.arcline_path_utils import discretize_lane, ArcLinePath # Recommended style to use as the plots will show grids. plt.style.use('seaborn-whitegrid') @@ -33,6 +34,8 @@ # Define a map geometry type for polygons and lines. Geometry = Union[Polygon, LineString] +locations = ['singapore-onenorth', 'singapore-hollandvillage', 'singapore-queenstown', 'boston-seaport'] + class NuScenesMap: """ @@ -64,13 +67,11 @@ def __init__(self, :param map_name: Which map out of `singapore-onenorth`, `singepore-hollandvillage`, `singapore-queenstown`, `boston-seaport` that we want to load. """ - assert map_name in ['singapore-onenorth', 'singapore-hollandvillage', 'singapore-queenstown', 'boston-seaport'] + assert map_name in locations, 'Error: Unknown map name %s!' % map_name self.dataroot = dataroot self.map_name = map_name - self.json_fname = os.path.join(self.dataroot, "maps", "{}.json".format(self.map_name)) - self.geometric_layers = ['polygon', 'line', 'node'] # These are the non-geometric layers which have polygons as the geometric descriptors. @@ -85,9 +86,20 @@ def __init__(self, self.non_geometric_layers = self.non_geometric_polygon_layers + self.non_geometric_line_layers self.layer_names = self.geometric_layers + self.lookup_polygon_layers + self.non_geometric_line_layers + # Load the selected map. + self.json_fname = os.path.join(self.dataroot, 'maps', 'expansion', '{}.json'.format(self.map_name)) with open(self.json_fname, 'r') as fh: self.json_obj = json.load(fh) + # Parse the map version and print an error for deprecated maps. + if 'version' in self.json_obj: + self.version = self.json_obj['version'] + else: + self.version = '1.0' + if self.version < '1.3': + raise Exception('Error: You are using an outdated map version (%s)! ' + 'Please go to https://www.nuscenes.org/download to download the latest map!') + self.canvas_edge = self.json_obj['canvas_edge'] self._load_layers() self._make_token2ind() @@ -95,15 +107,6 @@ def __init__(self, self.explorer = NuScenesMapExplorer(self) - # Parse the map version and print a warning for deprecated maps. - if 'version' in self.json_obj: - self.version = self.json_obj['version'] - else: - self.version = '1.0' - if self.version < '1.2': - raise Exception('Error: You are using an outdated map version! ' - 'Please go to https://www.nuscenes.org/download to download the latest map!') - def _load_layer(self, layer_name: str) -> List[dict]: """ Returns a list of records corresponding to the layer name. @@ -112,15 +115,13 @@ def _load_layer(self, layer_name: str) -> List[dict]: """ return self.json_obj[layer_name] - def _load_arcline_path(self,) -> Dict[str, List[ArcLinePath]]: + def _load_layer_dict(self, layer_name: str) -> Dict[str, Union[dict, list]]: """ - Returns a dictionary mapping arcline_path_3 token to arcline_path_3 record. - :return: Dictionary Mapping token to arcline_path_3. + Returns a dict of records corresponding to the layer name. + :param layer_name: Name of the layer that will be loaded. + :return: A dict of records corresponding to a layer. """ - return self.json_obj['arcline_path_3'] - - def _load_lane_connectivity(self) -> Dict[str, Dict[str, List[str]]]: - return self.json_obj['connectivity'] + return self.json_obj[layer_name] def _load_layers(self) -> None: """ Loads each available layer. """ @@ -140,9 +141,10 @@ def _load_layers(self) -> None: self.road_divider = self._load_layer('road_divider') self.lane_divider = self._load_layer('lane_divider') self.traffic_light = self._load_layer('traffic_light') - self.arcline_path_3 = self._load_arcline_path() + + self.arcline_path_3: Dict[str, List[dict]] = self._load_layer_dict('arcline_path_3') + self.connectivity: Dict[str, dict] = self._load_layer_dict('connectivity') self.lane_connector = self._load_layer('lane_connector') - self.connectivity = self._load_lane_connectivity() def _make_token2ind(self) -> None: """ Store the mapping from token to layer index for each layer. """ @@ -221,7 +223,8 @@ def render_record(self, token: str, alpha: float = 0.5, figsize: Tuple[float, float] = None, - other_layers: List[str] = None) -> Tuple[Figure, Tuple[Axes, Axes]]: + other_layers: List[str] = None, + bitmap: Optional[BitMap] = None) -> Tuple[Figure, Tuple[Axes, Axes]]: """ Render a single map record. By default will also render 3 layers which are `drivable_area`, `lane`, and `walkway` unless specified by `other_layers`. @@ -230,24 +233,29 @@ def render_record(self, :param alpha: The opacity of each layer that gets rendered. :param figsize: Size of the whole figure. :param other_layers: What other layers to render aside from the one specified in `layer_name`. + :param bitmap: Optional BitMap object to render below the other map layers. :return: The matplotlib figure and axes of the rendered layers. """ - return self.explorer.render_record(layer_name, token, alpha, figsize, other_layers) + return self.explorer.render_record(layer_name, token, alpha, + figsize=figsize, other_layers=other_layers, bitmap=bitmap) def render_layers(self, layer_names: List[str], alpha: float = 0.5, figsize: Union[None, float, Tuple[float, float]] = None, - tokens: List[str] = None) -> Tuple[Figure, Axes]: + tokens: List[str] = None, + bitmap: Optional[BitMap] = None) -> Tuple[Figure, Axes]: """ Render a list of layer names. :param layer_names: A list of layer names. :param alpha: The opacity of each layer that gets rendered. :param figsize: Size of the whole figure. :param tokens: Optional list of tokens to render. None means all tokens are rendered. + :param bitmap: Optional BitMap object to render below the other map layers. :return: The matplotlib figure and axes of the rendered layers. """ - return self.explorer.render_layers(layer_names, alpha, figsize, tokens) + return self.explorer.render_layers(layer_names, alpha, + figsize=figsize, tokens=tokens, bitmap=bitmap) def render_map_patch(self, box_coords: Tuple[float, float, float, float], @@ -255,7 +263,8 @@ def render_map_patch(self, alpha: float = 0.5, figsize: Tuple[int, int] = (15, 15), render_egoposes_range: bool = True, - render_legend: bool = True) -> Tuple[Figure, Axes]: + render_legend: bool = True, + bitmap: Optional[BitMap] = None) -> Tuple[Figure, Axes]: """ Renders a rectangular patch specified by `box_coords`. By default renders all layers. :param box_coords: The rectangular patch coordinates (x_min, y_min, x_max, y_max). @@ -264,10 +273,12 @@ def render_map_patch(self, :param figsize: Size of the whole figure. :param render_egoposes_range: Whether to render a rectangle around all ego poses. :param render_legend: Whether to render the legend of map layers. + :param bitmap: Optional BitMap object to render below the other map layers. :return: The matplotlib figure and axes of the rendered layers. """ - return self.explorer.render_map_patch(box_coords, layer_names, alpha, figsize, - render_egoposes_range, render_legend) + return self.explorer.render_map_patch(box_coords, layer_names=layer_names, alpha=alpha, figsize=figsize, + render_egoposes_range=render_egoposes_range, + render_legend=render_legend, bitmap=bitmap) def render_map_in_image(self, nusc: NuScenes, @@ -280,7 +291,7 @@ def render_map_in_image(self, render_outside_im: bool = True, layer_names: List[str] = None, verbose: bool = True, - out_path: str = None) -> None: + out_path: str = None) -> Tuple[Figure, Axes]: """ Render a nuScenes camera image and overlay the polygons for the specified map layers. Note that the projections are not always accurate as the localization is in 2d. @@ -297,10 +308,11 @@ def render_map_in_image(self, :param verbose: Whether to print to stdout. :param out_path: Optional path to save the rendered figure to disk. """ - self.explorer.render_map_in_image(nusc, sample_token, camera_channel=camera_channel, alpha=alpha, - patch_radius=patch_radius, min_polygon_area=min_polygon_area, - render_behind_cam=render_behind_cam, render_outside_im=render_outside_im, - layer_names=layer_names, verbose=verbose, out_path=out_path) + return self.explorer.render_map_in_image( + nusc, sample_token, camera_channel=camera_channel, alpha=alpha, + patch_radius=patch_radius, min_polygon_area=min_polygon_area, + render_behind_cam=render_behind_cam, render_outside_im=render_outside_im, + layer_names=layer_names, verbose=verbose, out_path=out_path) def render_egoposes_on_fancy_map(self, nusc: NuScenes, @@ -309,7 +321,8 @@ def render_egoposes_on_fancy_map(self, out_path: str = None, render_egoposes: bool = True, render_egoposes_range: bool = True, - render_legend: bool = True) -> np.ndarray: + render_legend: bool = True, + bitmap: Optional[BitMap] = None) -> Tuple[np.ndarray, Figure, Axes]: """ Renders each ego pose of a list of scenes on the map (around 40 poses per scene). This method is heavily inspired by NuScenes.render_egoposes_on_map(), but uses the map expansion pack maps. @@ -320,24 +333,27 @@ def render_egoposes_on_fancy_map(self, :param render_egoposes: Whether to render ego poses. :param render_egoposes_range: Whether to render a rectangle around all ego poses. :param render_legend: Whether to render the legend of map layers. + :param bitmap: Optional BitMap object to render below the other map layers. :return: . Returns a matrix with n ego poses in global map coordinates. """ return self.explorer.render_egoposes_on_fancy_map(nusc, scene_tokens=scene_tokens, verbose=verbose, out_path=out_path, render_egoposes=render_egoposes, render_egoposes_range=render_egoposes_range, - render_legend=render_legend) + render_legend=render_legend, bitmap=bitmap) def render_centerlines(self, resolution_meters: float = 0.5, - figsize: Union[None, float, Tuple[float, float]] = None) -> None: + figsize: Union[None, float, Tuple[float, float]] = None, + bitmap: Optional[BitMap] = None) -> Tuple[Figure, Axes]: """ Render the centerlines of all lanes and lane connectors. :param resolution_meters: How finely to discretize the lane. Smaller values ensure curved lanes are properly represented. :param figsize: Size of the figure. + :param bitmap: Optional BitMap object to render below the other map layers. """ - self.explorer.render_centerlines(resolution_meters=resolution_meters, figsize=figsize) + return self.explorer.render_centerlines(resolution_meters=resolution_meters, figsize=figsize, bitmap=bitmap) def render_map_mask(self, patch_box: Tuple[float, float, float, float], @@ -356,7 +372,8 @@ def render_map_mask(self, :param n_row: Number of rows with plots. :return: The matplotlib figure and a list of axes of the rendered layers. """ - return self.explorer.render_map_mask(patch_box, patch_angle, layer_names, canvas_size, + return self.explorer.render_map_mask(patch_box, patch_angle, + layer_names=layer_names, canvas_size=canvas_size, figsize=figsize, n_row=n_row) def get_map_mask(self, @@ -372,7 +389,7 @@ def get_map_mask(self, :param canvas_size: Size of the output mask (h, w). If None, we use the default resolution of 10px/m. :return: Stacked numpy array of size [c x h x w] with c channels and the same width/height as the canvas. """ - return self.explorer.get_map_mask(patch_box, patch_angle, layer_names, canvas_size) + return self.explorer.get_map_mask(patch_box, patch_angle, layer_names=layer_names, canvas_size=canvas_size) def get_map_geom(self, patch_box: Tuple[float, float, float, float], @@ -402,7 +419,7 @@ def get_records_in_patch(self, all non geometric records that are within the patch. :return: Dictionary of layer_name - tokens pairs. """ - return self.explorer.get_records_in_patch(box_coords, layer_names, mode) + return self.explorer.get_records_in_patch(box_coords, layer_names=layer_names, mode=mode) def is_record_in_patch(self, layer_name: str, @@ -418,16 +435,17 @@ def is_record_in_patch(self, return True if the geometric object is within the patch. :return: Boolean value on whether a particular record intersects or within a particular patch. """ - return self.explorer.is_record_in_patch(layer_name, token, box_coords, mode) + return self.explorer.is_record_in_patch(layer_name, token, box_coords, mode=mode) - def layers_on_point(self, x: float, y: float) -> Dict[str, str]: + def layers_on_point(self, x: float, y: float, layer_names: List[str] = None) -> Dict[str, str]: """ Returns all the polygonal layers that a particular point is on. :param x: x coordinate of the point of interest. :param y: y coordinate of the point of interest. + :param layer_names: The names of the layers to search for. :return: All the polygonal layers that a particular point is on. {: } """ - return self.explorer.layers_on_point(x, y) + return self.explorer.layers_on_point(x, y, layer_names=layer_names) def record_on_point(self, x: float, y: float, layer_name: str) -> str: """ @@ -435,7 +453,7 @@ def record_on_point(self, x: float, y: float, layer_name: str) -> str: :param x: x coordinate of the point of interest. :param y: y coordinate of the point of interest. :param layer_name: The non geometric polygonal layer name that we are interested in. - :return: The record token of a layer a particular point is on. + :return: The first token of a layer a particular point is on or '' if no layer is found. """ return self.explorer.record_on_point(x, y, layer_name) @@ -479,7 +497,7 @@ def get_records_in_radius(self, x: float, y: float, radius: float, """ patch = (x - radius, y - radius, x + radius, y + radius) - return self.explorer.get_records_in_patch(patch, layer_names, mode) + return self.explorer.get_records_in_patch(patch, layer_names, mode=mode) def discretize_centerlines(self, resolution_meters: float) -> List[np.array]: """ @@ -539,18 +557,20 @@ def get_incoming_lane_ids(self, lane_token: str) -> List[str]: return self._get_connected_lanes(lane_token, 'incoming') - def get_lane(self, lane_token: str) -> List[ArcLinePath]: + def get_arcline_path(self, lane_token: str) -> List[ArcLinePath]: """ - Get the arc line path representation for a lane. + Get the arcline path representation for a lane. + Note: This function was previously called `get_lane()`, but renamed to avoid confusion between lanes and + arcline paths. :param lane_token: Token for the lane. :return: Arc line path representation of the lane. """ - lane = self.arcline_path_3.get(lane_token) - if not lane: - raise ValueError(f'Lane token {lane_token} is not a valid lane.') + arcline_path = self.arcline_path_3.get(lane_token) + if not arcline_path: + raise ValueError(f'Error: Lane with token {lane_token} does not have a valid arcline path!') - return lane + return arcline_path def get_closest_lane(self, x: float, y: float, radius: float = 5) -> str: """ @@ -583,15 +603,17 @@ def render_next_roads(self, x: float, y: float, alpha: float = 0.5, - figsize: Union[None, float, Tuple[float, float]] = None) -> None: + figsize: Union[None, float, Tuple[float, float]] = None, + bitmap: Optional[BitMap] = None) -> Tuple[Figure, Axes]: """ Renders the possible next roads from a point of interest. :param x: x coordinate of the point of interest. :param y: y coordinate of the point of interest. :param alpha: The opacity of each layer that gets rendered. :param figsize: Size of the whole figure. + :param bitmap: Optional BitMap object to render below the other map layers. """ - self.explorer.render_next_roads(x, y, alpha, figsize) + return self.explorer.render_next_roads(x, y, alpha, figsize=figsize, bitmap=bitmap) def get_next_roads(self, x: float, y: float) -> Dict[str, List[str]]: """ @@ -683,22 +705,31 @@ def __init__(self, def render_centerlines(self, resolution_meters: float, - figsize: Union[None, float, Tuple[float, float]] = None) -> None: + figsize: Union[None, float, Tuple[float, float]] = None, + bitmap: Optional[BitMap] = None) -> Tuple[Figure, Axes]: """ Render the centerlines of all lanes and lane connectors. :param resolution_meters: How finely to discretize the lane. Smaller values ensure curved lanes are properly represented. :param figsize: Size of the figure. + :param bitmap: Optional BitMap object to render below the other map layers. """ # Discretize all lanes and lane connectors. pose_lists = self.map_api.discretize_centerlines(resolution_meters) # Render connectivity lines. - plt.figure(figsize=self._get_figsize(figsize)) + fig = plt.figure(figsize=self._get_figsize(figsize)) + ax = fig.add_axes([0, 0, 1, 1 / self.canvas_aspect_ratio]) + + if bitmap is not None: + bitmap.render(self.map_api.canvas_edge, ax) + for pose_list in pose_lists: if len(pose_list) > 0: plt.plot(pose_list[:, 0], pose_list[:, 1]) + return fig, ax + def render_map_mask(self, patch_box: Tuple[float, float, float, float], patch_angle: float, @@ -846,7 +877,8 @@ def render_record(self, token: str, alpha: float = 0.5, figsize: Union[None, float, Tuple[float, float]] = None, - other_layers: List[str] = None) -> Tuple[Figure, Tuple[Axes, Axes]]: + other_layers: List[str] = None, + bitmap: Optional[BitMap] = None) -> Tuple[Figure, Tuple[Axes, Axes]]: """ Render a single map record. By default will also render 3 layers which are `drivable_area`, `lane`, and `walkway` unless specified by @@ -856,6 +888,7 @@ def render_record(self, :param alpha: The opacity of each layer that gets rendered. :param figsize: Size of the whole figure. :param other_layers: What other layers to render aside from the one specified in `layer_name`. + :param bitmap: Optional BitMap object to render below the other map layers. :return: The matplotlib figure and axes of the rendered layers. """ if other_layers is None: @@ -880,6 +913,10 @@ def render_record(self, # To make sure the sequence of the layer overlays is always consistent after typesetting set(). random.seed('nutonomy') + if bitmap is not None: + bitmap.render(self.map_api.canvas_edge, global_ax) + bitmap.render(self.map_api.canvas_edge, local_ax) + layer_names = other_layers + [layer_name] layer_names = list(set(layer_names)) @@ -920,13 +957,15 @@ def render_layers(self, layer_names: List[str], alpha: float, figsize: Union[None, float, Tuple[float, float]], - tokens: List[str] = None) -> Tuple[Figure, Axes]: + tokens: List[str] = None, + bitmap: Optional[BitMap] = None) -> Tuple[Figure, Axes]: """ Render a list of layers. :param layer_names: A list of layer names. :param alpha: The opacity of each layer. :param figsize: Size of the whole figure. :param tokens: Optional list of tokens to render. None means all tokens are rendered. + :param bitmap: Optional BitMap object to render below the other map layers. :return: The matplotlib figure and axes of the rendered layers. """ fig = plt.figure(figsize=self._get_figsize(figsize)) @@ -935,8 +974,10 @@ def render_layers(self, ax.set_xlim(self.canvas_min_x, self.canvas_max_x) ax.set_ylim(self.canvas_min_y, self.canvas_max_y) - layer_names = list(set(layer_names)) + if bitmap is not None: + bitmap.render(self.map_api.canvas_edge, ax) + layer_names = list(set(layer_names)) for layer_name in layer_names: self._render_layer(ax, layer_name, alpha, tokens) @@ -950,7 +991,8 @@ def render_map_patch(self, alpha: float = 0.5, figsize: Tuple[float, float] = (15, 15), render_egoposes_range: bool = True, - render_legend: bool = True) -> Tuple[Figure, Axes]: + render_legend: bool = True, + bitmap: Optional[BitMap] = None) -> Tuple[Figure, Axes]: """ Renders a rectangular patch specified by `box_coords`. By default renders all layers. :param box_coords: The rectangular patch coordinates (x_min, y_min, x_max, y_max). @@ -959,6 +1001,7 @@ def render_map_patch(self, :param figsize: Size of the whole figure. :param render_egoposes_range: Whether to render a rectangle around all ego poses. :param render_legend: Whether to render the legend of map layers. + :param bitmap: Optional BitMap object to render below the other map layers. :return: The matplotlib figure and axes of the rendered layers. """ x_min, y_min, x_max, y_max = box_coords @@ -975,6 +1018,9 @@ def render_map_patch(self, ax = fig.add_axes([0, 0, 1, 1 / local_aspect_ratio]) + if bitmap is not None: + bitmap.render(self.map_api.canvas_edge, ax) + for layer_name in layer_names: self._render_layer(ax, layer_name, alpha) @@ -1007,7 +1053,7 @@ def render_map_in_image(self, render_outside_im: bool = True, layer_names: List[str] = None, verbose: bool = True, - out_path: str = None) -> None: + out_path: str = None) -> Tuple[Figure, Axes]: """ Render a nuScenes camera image and overlay the polygons for the specified map layers. Note that the projections are not always accurate as the localization is in 2d. @@ -1151,6 +1197,8 @@ def render_map_in_image(self, plt.tight_layout() plt.savefig(out_path, bbox_inches='tight', pad_inches=0) + return fig, ax + def render_egoposes_on_fancy_map(self, nusc: NuScenes, scene_tokens: List = None, @@ -1158,7 +1206,8 @@ def render_egoposes_on_fancy_map(self, out_path: str = None, render_egoposes: bool = True, render_egoposes_range: bool = True, - render_legend: bool = True) -> np.ndarray: + render_legend: bool = True, + bitmap: Optional[BitMap] = None) -> Tuple[np.ndarray, Figure, Axes]: """ Renders each ego pose of a list of scenes on the map (around 40 poses per scene). This method is heavily inspired by NuScenes.render_egoposes_on_map(), but uses the map expansion pack maps. @@ -1171,6 +1220,7 @@ def render_egoposes_on_fancy_map(self, :param render_egoposes: Whether to render ego poses. :param render_egoposes_range: Whether to render a rectangle around all ego poses. :param render_legend: Whether to render the legend of map layers. + :param bitmap: Optional BitMap object to render below the other map layers. :return: . Returns a matrix with n ego poses in global map coordinates. """ # Settings @@ -1182,7 +1232,7 @@ def render_egoposes_on_fancy_map(self, # Get logs by location. log_location = self.map_api.map_name - log_tokens = [l['token'] for l in nusc.log if l['location'] == log_location] + log_tokens = [log['token'] for log in nusc.log if log['location'] == log_location] assert len(log_tokens) > 0, 'Error: This split has 0 scenes for location %s!' % log_location # Filter scenes. @@ -1239,7 +1289,7 @@ def render_egoposes_on_fancy_map(self, my_patch = (min_patch[0], min_patch[1], max_patch[0], max_patch[1]) fig, ax = self.render_map_patch(my_patch, self.map_api.non_geometric_layers, figsize=(10, 10), render_egoposes_range=render_egoposes_range, - render_legend=render_legend) + render_legend=render_legend, bitmap=bitmap) # Plot in the same axis as the map. # Make sure these are plotted "on top". @@ -1250,19 +1300,21 @@ def render_egoposes_on_fancy_map(self, if out_path is not None: plt.savefig(out_path, bbox_inches='tight', pad_inches=0) - return map_poses + return map_poses, fig, ax def render_next_roads(self, x: float, y: float, alpha: float = 0.5, - figsize: Union[None, float, Tuple[float, float]] = None) -> None: + figsize: Union[None, float, Tuple[float, float]] = None, + bitmap: Optional[BitMap] = None) -> Tuple[Figure, Axes]: """ Renders the possible next roads from a point of interest. :param x: x coordinate of the point of interest. :param y: y coordinate of the point of interest. :param alpha: The opacity of each layer that gets rendered. :param figsize: Size of the whole figure. + :param bitmap: Optional BitMap object to render below the other map layers. """ # Get next roads. next_roads = self.map_api.get_next_roads(x, y) @@ -1274,11 +1326,13 @@ def render_next_roads(self, tokens.extend(layer_tokens) # Render them. - fig, ax = self.render_layers(layer_names, alpha, figsize, tokens) + fig, ax = self.render_layers(layer_names, alpha, figsize, tokens=tokens, bitmap=bitmap) # Render current location with an x. ax.plot(x, y, 'x', markersize=12, color='red') + return fig, ax + @staticmethod def _clip_points_behind_camera(points, near_plane: float): """ @@ -1398,20 +1452,25 @@ def is_record_in_patch(self, else: raise ValueError("{} is not a valid layer".format(layer_name)) - def layers_on_point(self, x: float, y: float) -> Dict[str, str]: + def layers_on_point(self, x: float, y: float, layer_names: List[str] = None) -> Dict[str, str]: """ Returns all the polygonal layers that a particular point is on. :param x: x coordinate of the point of interest. :param y: y coordinate of the point of interest. + :param layer_names: The names of the layers to search for. :return: All the polygonal layers that a particular point is on. """ + # Default option. + if layer_names is None: + layer_names = self.map_api.non_geometric_polygon_layers + layers_on_point = dict() - for layer_name in self.map_api.non_geometric_polygon_layers: + for layer_name in layer_names: layers_on_point.update({layer_name: self.record_on_point(x, y, layer_name)}) return layers_on_point - def record_on_point(self, x, y, layer_name) -> str: + def record_on_point(self, x: float, y: float, layer_name: str) -> str: """ Query what record of a layer a particular point is on. :param x: x coordinate of the point of interest. diff --git a/python-sdk/nuscenes/map_expansion/tests/init_all_maps.py b/python-sdk/nuscenes/map_expansion/tests/init_all_maps.py deleted file mode 100644 index d2fbb70b..00000000 --- a/python-sdk/nuscenes/map_expansion/tests/init_all_maps.py +++ /dev/null @@ -1,10 +0,0 @@ -import unittest - -from nuscenes.map_expansion.map_api import NuScenesMap - - -class TestInitAllMaps(unittest.TestCase): - - def test_init_all_maps(self): - for my_map in ['singapore-onenorth', 'singapore-hollandvillage', 'singapore-queenstown', 'boston-seaport']: - nusc_map = NuScenesMap(map_name=my_map) diff --git a/python-sdk/nuscenes/map_expansion/tests/test_all_maps.py b/python-sdk/nuscenes/map_expansion/tests/test_all_maps.py new file mode 100644 index 00000000..3da14cd4 --- /dev/null +++ b/python-sdk/nuscenes/map_expansion/tests/test_all_maps.py @@ -0,0 +1,88 @@ +import os +import unittest +from collections import defaultdict + +import matplotlib.pyplot as plt +import tqdm + +from nuscenes.map_expansion.map_api import NuScenesMap, locations +from nuscenes.map_expansion.utils import get_egoposes_on_drivable_ratio, get_disconnected_lanes +from nuscenes.nuscenes import NuScenes + + +class TestAllMaps(unittest.TestCase): + version = 'v1.0-mini' + render = False + + def setUp(self): + """ Initialize the map for each location. """ + + self.nusc_maps = dict() + for map_name in locations: + # Load map. + nusc_map = NuScenesMap(map_name=map_name, dataroot=os.environ['NUSCENES']) + + # Render for debugging. + if self.render: + nusc_map.render_layers(['lane'], figsize=1) + plt.show() + + self.nusc_maps[map_name] = nusc_map + + def test_layer_stats(self): + """ Test if each layer has the right number of instances. This is useful to compare between map versions. """ + layer_counts = defaultdict(lambda: []) + ref_counts = { + 'singapore-onenorth': [1, 783, 645, 936, 120, 838, 451, 39, 152, 357, 127], + 'singapore-hollandvillage': [426, 167, 387, 601, 28, 498, 300, 0, 107, 220, 119], + 'singapore-queenstown': [219, 260, 676, 910, 75, 457, 437, 40, 172, 257, 81], + 'boston-seaport': [2, 928, 969, 1215, 340, 301, 775, 275, 377, 671, 307] + } + + for map_name in locations: + nusc_map = self.nusc_maps[map_name] + for layer_name in nusc_map.non_geometric_layers: + layer_objs = nusc_map.json_obj[layer_name] + layer_counts[map_name].append(len(layer_objs)) + + assert ref_counts[map_name] == layer_counts[map_name], \ + 'Error: Map %s has a different number of layers: \n%s vs. \n%s' % \ + (map_name, ref_counts[map_name], layer_counts[map_name]) + + @unittest.skip # This test is known to fail on dozens of disconnected lanes. + def test_disconnected_lanes(self): + """ Check if any lanes are disconnected. """ + found_error = False + for map_name in locations: + nusc_map = self.nusc_maps[map_name] + disconnected = get_disconnected_lanes(nusc_map) + if len(disconnected) > 0: + print('Error: Missing connectivity in map %s for %d lanes: \n%s' + % (map_name, len(disconnected), disconnected)) + found_error = True + self.assertFalse(found_error, 'Error: Found missing connectivity. See messages above!') + + def test_egoposes_on_map(self): + """ Test that all ego poses land on """ + nusc = NuScenes(version=self.version, dataroot=os.environ['NUSCENES'], verbose=False) + whitelist = ['scene-0499', 'scene-0501', 'scene-0502', 'scene-0515', 'scene-0517'] + + invalid_scenes = [] + for scene in tqdm.tqdm(nusc.scene): + if scene['name'] in whitelist: + continue + + log = nusc.get('log', scene['log_token']) + map_name = log['location'] + nusc_map = self.nusc_maps[map_name] + ratio_valid = get_egoposes_on_drivable_ratio(nusc, nusc_map, scene['token']) + if ratio_valid != 1.0: + print('Error: Scene %s has a ratio of %f ego poses on the driveable area!' + % (scene['name'], ratio_valid)) + invalid_scenes.append(scene['name']) + + self.assertEqual(len(invalid_scenes), 0) + + +if __name__ == '__main__': + unittest.main() diff --git a/python-sdk/nuscenes/map_expansion/utils.py b/python-sdk/nuscenes/map_expansion/utils.py new file mode 100644 index 00000000..1d5f5010 --- /dev/null +++ b/python-sdk/nuscenes/map_expansion/utils.py @@ -0,0 +1,142 @@ +from typing import List, Dict, Set + +from nuscenes.map_expansion.map_api import NuScenesMap +from nuscenes.nuscenes import NuScenes + + +def get_egoposes_on_drivable_ratio(nusc: NuScenes, nusc_map: NuScenesMap, scene_token: str) -> float: + """ + Get the ratio of ego poses on the drivable area. + :param nusc: A NuScenes instance. + :param nusc_map: The NuScenesMap instance of a particular map location. + :param scene_token: The token of the current scene. + :return: The ratio of poses that fall on the driveable area. + """ + + # Go through each sample in the scene. + sample_tokens = nusc.field2token('sample', 'scene_token', scene_token) + poses_all = 0 + poses_valid = 0 + for sample_token in sample_tokens: + + # Poses are associated with the sample_data. Here we use the lidar sample_data. + sample_record = nusc.get('sample', sample_token) + sample_data_record = nusc.get('sample_data', sample_record['data']['LIDAR_TOP']) + pose_record = nusc.get('ego_pose', sample_data_record['ego_pose_token']) + + # Check if the ego pose is on the driveable area. + ego_pose = pose_record['translation'][:2] + record = nusc_map.record_on_point(ego_pose[0], ego_pose[1], 'drivable_area') + if len(record) > 0: + poses_valid += 1 + poses_all += 1 + ratio_valid = poses_valid / poses_all + + return ratio_valid + + +def get_disconnected_subtrees(connectivity: Dict[str, dict]) -> Set[str]: + """ + Compute lanes or lane_connectors that are part of disconnected subtrees. + :param connectivity: The connectivity of the current NuScenesMap. + :return: The lane_tokens for lanes that are part of a disconnected subtree. + """ + # Init. + connected = set() + pending = set() + + # Add first lane. + all_keys = list(connectivity.keys()) + first_key = all_keys[0] + all_keys = set(all_keys) + pending.add(first_key) + + while len(pending) > 0: + # Get next lane. + lane_token = pending.pop() + connected.add(lane_token) + + # Add lanes connected to this lane. + if lane_token in connectivity: + incoming = connectivity[lane_token]['incoming'] + outgoing = connectivity[lane_token]['outgoing'] + inout_lanes = set(incoming + outgoing) + for other_lane_token in inout_lanes: + if other_lane_token not in connected: + pending.add(other_lane_token) + + disconnected = all_keys - connected + assert len(disconnected) < len(connected), 'Error: Bad initialization chosen!' + return disconnected + + +def drop_disconnected_lanes(nusc_map: NuScenesMap) -> NuScenesMap: + """ + Remove any disconnected lanes. + Note: This function is currently not used and we do not recommend using it. Some lanes that we do not drive on are + disconnected from the other lanes. Removing them would create a single connected graph. It also removes + meaningful information, which is why we do not drop these. + :param nusc_map: The NuScenesMap instance of a particular map location. + :return: The cleaned NuScenesMap instance. + """ + + # Get disconnected lanes. + disconnected = get_disconnected_lanes(nusc_map) + + # Remove lane. + nusc_map.lane = [lane for lane in nusc_map.lane if lane['token'] not in disconnected] + + # Remove lane_connector. + nusc_map.lane_connector = [lane for lane in nusc_map.lane_connector if lane['token'] not in disconnected] + + # Remove connectivity entries. + for lane_token in disconnected: + if lane_token in nusc_map.connectivity: + del nusc_map.connectivity[lane_token] + + # Remove arcline_path_3. + for lane_token in disconnected: + if lane_token in nusc_map.arcline_path_3: + del nusc_map.arcline_path_3[lane_token] + + # Remove connectivity references. + empty_connectivity = [] + for lane_token, connectivity in nusc_map.connectivity.items(): + connectivity['incoming'] = [i for i in connectivity['incoming'] if i not in disconnected] + connectivity['outgoing'] = [o for o in connectivity['outgoing'] if o not in disconnected] + if len(connectivity['incoming']) + len(connectivity['outgoing']) == 0: + empty_connectivity.append(lane_token) + for lane_token in empty_connectivity: + del nusc_map.connectivity[lane_token] + + # To fix the map class, we need to update some indices. + nusc_map._make_token2ind() + + return nusc_map + + +def get_disconnected_lanes(nusc_map: NuScenesMap) -> List[str]: + """ + Get a list of all disconnected lanes and lane_connectors. + :param nusc_map: The NuScenesMap instance of a particular map location. + :return: A list of lane or lane_connector tokens. + """ + disconnected = set() + for lane_token, connectivity in nusc_map.connectivity.items(): + # Lanes which are disconnected. + inout_lanes = connectivity['incoming'] + connectivity['outgoing'] + if len(inout_lanes) == 0: + disconnected.add(lane_token) + continue + + # Lanes that only exist in connectivity (not currently an issue). + for inout_lane_token in inout_lanes: + if inout_lane_token not in nusc_map._token2ind['lane'] and \ + inout_lane_token not in nusc_map._token2ind['lane_connector']: + disconnected.add(inout_lane_token) + + # Lanes that are part of disconnected subtrees. + subtrees = get_disconnected_subtrees(nusc_map.connectivity) + disconnected = disconnected.union(subtrees) + + return sorted(list(disconnected)) diff --git a/python-sdk/nuscenes/prediction/input_representation/static_layers.py b/python-sdk/nuscenes/prediction/input_representation/static_layers.py index 83c8b330..181f22d9 100644 --- a/python-sdk/nuscenes/prediction/input_representation/static_layers.py +++ b/python-sdk/nuscenes/prediction/input_representation/static_layers.py @@ -9,7 +9,7 @@ from pyquaternion import Quaternion from nuscenes.eval.common.utils import quaternion_yaw -from nuscenes.map_expansion.map_api import NuScenesMap +from nuscenes.map_expansion.map_api import NuScenesMap, locations from nuscenes.prediction import PredictHelper from nuscenes.prediction.helper import angle_of_rotation, angle_diff from nuscenes.prediction.input_representation.combinators import Rasterizer @@ -28,14 +28,9 @@ def load_all_maps(helper: PredictHelper, verbose: bool = False) -> Dict[str, NuS :return: Mapping from map-name to the NuScenesMap api instance. """ dataroot = helper.data.dataroot - - json_files = filter(lambda f: "json" in f and "prediction_scenes" not in f, - os.listdir(os.path.join(dataroot, "maps"))) maps = {} - for map_file in json_files: - - map_name = str(map_file.split(".")[0]) + for map_name in locations: if verbose: print(f'static_layers.py - Loading Map: {map_name}') diff --git a/python-sdk/nuscenes/scripts/export_2d_annotations_as_json.py b/python-sdk/nuscenes/scripts/export_2d_annotations_as_json.py index cdb90664..b69d0d58 100644 --- a/python-sdk/nuscenes/scripts/export_2d_annotations_as_json.py +++ b/python-sdk/nuscenes/scripts/export_2d_annotations_as_json.py @@ -174,7 +174,7 @@ def main(args): # For debugging purposes: Only produce the first n images. if args.image_limit != -1: - sample_data_camera_tokens = sample_data_camera_tokens[:args.image_limit] + sample_data_camera_tokens = sample_data_camera_tokens[:args.image_limit] # Loop through the records and apply the re-projection algorithm. reprojections = [] diff --git a/python-sdk/nuscenes/scripts/export_egoposes_on_map.py b/python-sdk/nuscenes/scripts/export_egoposes_on_map.py index f6c8f832..756e17cd 100644 --- a/python-sdk/nuscenes/scripts/export_egoposes_on_map.py +++ b/python-sdk/nuscenes/scripts/export_egoposes_on_map.py @@ -18,7 +18,7 @@ def export_ego_poses(nusc: NuScenes, out_dir: str): """ Script to render where ego vehicle drives on the maps """ # Load NuScenes locations - locations = np.unique([l['location'] for l in nusc.log]) + locations = np.unique([log['location'] for log in nusc.log]) # Create output directory if not os.path.isdir(out_dir): diff --git a/python-sdk/nuscenes/tests/test_predict_helper.py b/python-sdk/nuscenes/tests/test_predict_helper.py index ef9bef81..ddc67af2 100644 --- a/python-sdk/nuscenes/tests/test_predict_helper.py +++ b/python-sdk/nuscenes/tests/test_predict_helper.py @@ -27,7 +27,8 @@ def get(self, table_name: str, token: str) -> Dict[str, Any]: assert table_name in {'sample_annotation', 'sample'} return getattr(self, "_" + table_name)[token] -class Test_convert_coords(unittest.TestCase): + +class TestConvertCoords(unittest.TestCase): def setUp(self): along_pos_x = np.zeros((5, 2)) @@ -373,7 +374,6 @@ def setUp(self): 'prev': '4b', 'next': '6b'}, {'token': '6b', 'instance_token': '2', 'sample_token': '6', 'translation': [11, 11, 11], 'prev': '5b', 'next': ''}] - def test_get_sample_annotation(self,): mock_annotation = {'token': '1', 'instance_token': 'instance_1', @@ -385,7 +385,6 @@ def test_get_sample_annotation(self,): helper = PredictHelper(nusc) self.assertDictEqual(mock_annotation, helper.get_sample_annotation('instance_1', 'sample_1')) - def test_get_future_for_agent_exact_amount(self,): mock_samples = [{'token': '1', 'timestamp': 0}, diff --git a/python-sdk/tutorials/map_expansion_tutorial.ipynb b/python-sdk/tutorials/map_expansion_tutorial.ipynb index adfc04c1..95d6a1f5 100644 --- a/python-sdk/tutorials/map_expansion_tutorial.ipynb +++ b/python-sdk/tutorials/map_expansion_tutorial.ipynb @@ -47,6 +47,7 @@ "\n", "from nuscenes.map_expansion.map_api import NuScenesMap\n", "from nuscenes.map_expansion import arcline_path_utils\n", + "from nuscenes.map_expansion.bitmap import BitMap\n", "\n", "nusc_map = NuScenesMap(dataroot='/data/sets/nuscenes', map_name='singapore-onenorth')" ] @@ -85,6 +86,24 @@ "fig, ax = nusc_map.render_layers(nusc_map.non_geometric_layers, figsize=1)" ] }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### Rendering the lidar basemap\n", + "**New:** We can render the HD lidar basemap used for localization. The basemap is a bitmap image that can be underlaid for most functions (`render_centerlines`, `render_egoposes_on_fancy_map`, `render_layers`, `render_map_patch`, `render_next_roads`, `render_record`). The same `BitMap` class can also be used to render the semantic prior (drivable surface + sidewalk) from the original nuScenes release. Note that in this visualization we only show the `lane` annotations for better visibility." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "bitmap = BitMap(nusc_map.dataroot, nusc_map.map_name, 'basemap')\n", + "fig, ax = nusc_map.render_layers(['lane'], figsize=1, bitmap=bitmap)" + ] + }, { "cell_type": "markdown", "metadata": {}, @@ -102,7 +121,7 @@ }, "outputs": [], "source": [ - "fig, ax = nusc_map.render_record('stop_line', nusc_map.stop_line[14]['token'])" + "fig, ax = nusc_map.render_record('stop_line', nusc_map.stop_line[14]['token'], other_layers=[], bitmap=bitmap)" ] }, { @@ -243,7 +262,7 @@ "metadata": {}, "outputs": [], "source": [ - "nusc_map.render_next_roads(x, y, figsize=1)" + "nusc_map.render_next_roads(x, y, figsize=1, bitmap=bitmap)" ] }, { @@ -260,7 +279,7 @@ "metadata": {}, "outputs": [], "source": [ - "nusc_map.render_centerlines(resolution_meters=0.5, figsize=1)" + "nusc_map.render_centerlines(resolution_meters=0.5, figsize=1, bitmap=bitmap)" ] }, { @@ -288,7 +307,7 @@ "metadata": {}, "outputs": [], "source": [ - "lane_record = nusc_map.get_lane(closest_lane)\n", + "lane_record = nusc_map.get_arcline_path(closest_lane)\n", "lane_record" ] }, @@ -417,7 +436,7 @@ "outputs": [], "source": [ "my_patch = (300, 1000, 500, 1200)\n", - "fig, ax = nusc_map.render_map_patch(my_patch, nusc_map.non_geometric_layers, figsize=(10, 10))" + "fig, ax = nusc_map.render_map_patch(my_patch, nusc_map.non_geometric_layers, figsize=(10, 10), bitmap=bitmap)" ] }, { diff --git a/python-sdk/tutorials/prediction_tutorial.ipynb b/python-sdk/tutorials/prediction_tutorial.ipynb index 44e193ef..eb4475b7 100644 --- a/python-sdk/tutorials/prediction_tutorial.ipynb +++ b/python-sdk/tutorials/prediction_tutorial.ipynb @@ -238,7 +238,7 @@ "metadata": {}, "outputs": [], "source": [ - "lane_record = nusc_map.get_lane(closest_lane)\n", + "lane_record = nusc_map.get_arcline_path(closest_lane)\n", "lane_record" ] },