This is the tutorial for the nuScenes map expansion. In particular, the NuScenesMap
data class.
This tutorial will go through the description of each layers, how we retrieve and query a certain record within the map layers, render methods, and advanced data exploration
In database terms, layers are basically tables of the map database in which we assign arbitrary parts of the maps with informative labels such as traffic_light
, stop_line
, walkway
, etc. Refer to the discussion on layers for more details.
To install the map expansion, please download the files from https://www.nuscenes.org/download and copy the files into your nuScenes map folder, e.g. /data/sets/nuscenes/maps
.
We will be working with the singapore-onenorth
map. The NuScenesMap
can be initialized as follows:
import matplotlib.pyplot as plt
import tqdm
import numpy as np
from nuscenes.map_expansion.map_api import NuScenesMap
from nuscenes.map_expansion import arcline_path_utils
from nuscenes.map_expansion.bitmap import BitMap
nusc_map = NuScenesMap(dataroot='/data/sets/nuscenes', map_name='singapore-onenorth')
Before we go into the details, let's visualize the map.
The NuScenesMap
class makes it possible to render multiple map layers on a matplotlib figure.
fig, ax = nusc_map.render_layers(nusc_map.non_geometric_layers, figsize=1)
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.
bitmap = BitMap(nusc_map.dataroot, nusc_map.map_name, 'basemap')
fig, ax = nusc_map.render_layers(['lane'], figsize=1, bitmap=bitmap)
We can render a record, which will show its global and local view
fig, ax = nusc_map.render_record('stop_line', nusc_map.stop_line[14]['token'], other_layers=[], bitmap=bitmap)
The NuScenesMap
class makes it possible to convert multiple map layers into binary mask and render on a Matplotlib figure. First let's call get_map_mask
to look at the raw data of two layers:
patch_box = (300, 1700, 100, 100)
patch_angle = 0 # Default orientation where North is up
layer_names = ['drivable_area', 'walkway']
canvas_size = (1000, 1000)
map_mask = nusc_map.get_map_mask(patch_box, patch_angle, layer_names, canvas_size)
map_mask[0]
array([[0, 0, 0, ..., 0, 0, 0], [0, 0, 0, ..., 0, 0, 0], [0, 0, 0, ..., 0, 0, 0], ..., [0, 0, 0, ..., 1, 1, 1], [0, 0, 0, ..., 1, 1, 1], [0, 0, 0, ..., 1, 1, 1]], dtype=uint8)
Now we directly visualize the map mask retrieved above using render_map_mask
:
figsize = (12, 4)
fig, ax = nusc_map.render_map_mask(patch_box, patch_angle, layer_names, canvas_size, figsize=figsize, n_row=1)
We can also render the same map rotated by 45 degrees clockwise:
fig, ax = nusc_map.render_map_mask(patch_box, 45, layer_names, canvas_size, figsize=figsize, n_row=1)
Let us take a nuScenes camera image and overlay the relevant map layers. Note that the projections are not perfect if the ground is uneven as the localization is 2d.
# Init nuScenes. Requires the dataset to be stored on disk.
from nuscenes.nuscenes import NuScenes
nusc = NuScenes(version='v1.0-mini', verbose=False)
# Pick a sample and render the front camera image.
sample_token = nusc.sample[9]['token']
layer_names = ['road_segment', 'lane', 'ped_crossing', 'walkway', 'stop_line', 'carpark_area']
camera_channel = 'CAM_FRONT'
nusc_map.render_map_in_image(nusc, sample_token, layer_names=layer_names, camera_channel=camera_channel)
Warning: Note that the projections are not always accurate as the localization is in 2d.
(<Figure size 648x1152 with 1 Axes>, <matplotlib.axes._axes.Axes at 0x7ff40ca352d0>)
We can also plot the ego poses onto the map. This requires us to load up the NuScenes
class, which can take some time.
# Init NuScenes. Requires the dataset to be stored on disk.
from nuscenes.nuscenes import NuScenes
nusc = NuScenes(version='v1.0-mini', verbose=False)
# Render ego poses.
nusc_map_bos = NuScenesMap(dataroot='/data/sets/nuscenes', map_name='boston-seaport')
ego_poses = nusc_map_bos.render_egoposes_on_fancy_map(nusc, scene_tokens=[nusc.scene[1]['token']], verbose=False)
We also provide functions for navigation around the road network. For this purpose, the road layers lane
, road_block
and road_segment
are especially useful (see definitions below). The get_next_roads(x, y)
function looks at the road layer at a particular point. It then retrieves the next road object in the direction of the lane
or road_block
. As road_segments
do not have a direction (e.g. intersections), we return all possible next roads.
x = 873
y = 1286
print('Road objects on selected point:', nusc_map.layers_on_point(x, y), '\n')
print('Next road objects:', nusc_map.get_next_roads(x, y))
Road objects on selected point: {'drivable_area': 'c3e28556-b711-4581-9970-b66166fb907d', 'road_segment': '57416e99-8919-4a28-985b-033a16938243', 'road_block': '', 'lane': '', 'ped_crossing': '', 'walkway': '', 'stop_line': '', 'carpark_area': ''} Next road objects: {'road_segment': ['3493d68c-5217-4d21-ae1b-3cbf4467dd77', '4b0e50c0-c549-49a2-9077-57a8cba8ab55', '5428b143-6343-4045-ac81-466df3dcc510'], 'road_block': ['5c286ee8-7b4d-4cd8-84bb-7486e77ba827', '8b33213a-692e-4c5f-a69a-efa6836f5316', '9aa7a714-30ba-4892-a276-c033928a8ae2', '9c506cc4-7d14-475d-8063-22a5b9bc257f', 'b7cc94f4-3882-4df2-a9ae-9349925809a1', 'e0c4f027-ea81-40f2-bafc-3fb8e8ab78c3'], 'lane': ['525b6716-a12e-4dd0-8541-91ef672ce39b', '5fdd162d-477d-4bc4-ada3-535d79a9f4b1', '8658217b-87d6-4f8b-96be-35d53100247d', 'b7378bda-dedf-4f97-9d87-b0dd602fdab5', 'bce7caf7-5e33-48d6-b0aa-8b5b641c8ce5', 'f747ce8a-2396-4da3-a8e6-45201ed470d6']}
We can also visualize the next roads using the render_next_roads(x, y)
function. We see that there are 3 adjacent roads to the intersection specified by (x, y).
nusc_map.render_next_roads(x, y, figsize=1, bitmap=bitmap)
(<Figure size 729x570.816 with 1 Axes>, <matplotlib.axes._axes.Axes at 0x7ff410849150>)
For the prediction challenge we added connectivity information to the map expansion (v1.2) to efficiently query which lane is connected to which other lanes. Below we render the lane and lane_connector objects. The lanes and lane_connectors are defined by parametric curves. The resolution_meters
parameter specifies the discretization resolution of the curve. If we set it to a high value (e.g. 100), the curves will appear as straight lines. We recommend setting this value to 1m or less.
nusc_map.render_centerlines(resolution_meters=0.5, figsize=1, bitmap=bitmap)
(<Figure size 729x570.816 with 1 Axes>, <matplotlib.axes._axes.Axes at 0x7ff410849a90>)
To get the closest lane to a location, use the get_closest_lane
method. To see the internal data representation of the lane, use the get_lane_record
method.
You can also explore the connectivity of the lanes, with the get_outgoing_lanes
and get_incoming_lane
methods.
x, y, yaw = 395, 1095, 0
closest_lane = nusc_map.get_closest_lane(x, y, radius=2)
closest_lane
'5933500a-f0f2-4d69-9bbc-83b875e4a73e'
lane_record = nusc_map.get_arcline_path(closest_lane)
lane_record
[{'start_pose': [421.2419602954602, 1087.9127960414617, 2.739593514975998], 'end_pose': [391.7142849867393, 1100.464077182952, 2.7365754617298705], 'shape': 'LSR', 'radius': 999.999, 'segment_length': [0.23651121617864976, 28.593481378991886, 3.254561444252876]}]
nusc_map.get_incoming_lane_ids(closest_lane)
['f24a067b-d650-47d0-8664-039d648d7c0d']
nusc_map.get_outgoing_lane_ids(closest_lane)
['0282d0e3-b6bf-4bcd-be24-35c9ce4c6591', '28d15254-0ef9-48c3-9e06-dc5a25b31127']
To help manipulate the lanes, we've added an arcline_path_utils
module. For example, something you might want to do is discretize a lane into a sequence of poses.
poses = arcline_path_utils.discretize_lane(lane_record, resolution_meters=1)
poses
[(421.2419602954602, 1087.9127960414617, 2.739593514975998), (420.34712994585345, 1088.2930152148274, 2.739830026428688), (419.45228865726136, 1088.6732086473173, 2.739830026428688), (418.5574473686693, 1089.0534020798073, 2.739830026428688), (417.66260608007724, 1089.433595512297, 2.739830026428688), (416.76776479148515, 1089.813788944787, 2.739830026428688), (415.87292350289306, 1090.1939823772768, 2.739830026428688), (414.97808221430097, 1090.5741758097668, 2.739830026428688), (414.0832409257089, 1090.9543692422567, 2.739830026428688), (413.1883996371168, 1091.3345626747464, 2.739830026428688), (412.29355834852475, 1091.7147561072363, 2.739830026428688), (411.39871705993266, 1092.0949495397263, 2.739830026428688), (410.5038757713406, 1092.4751429722162, 2.739830026428688), (409.6090344827485, 1092.8553364047061, 2.739830026428688), (408.7141931941564, 1093.2355298371958, 2.739830026428688), (407.81935190556436, 1093.6157232696858, 2.739830026428688), (406.92451061697227, 1093.9959167021757, 2.739830026428688), (406.0296693283802, 1094.3761101346656, 2.739830026428688), (405.1348280397881, 1094.7563035671556, 2.739830026428688), (404.239986751196, 1095.1364969996453, 2.739830026428688), (403.3451454626039, 1095.5166904321352, 2.739830026428688), (402.4503041740119, 1095.8968838646251, 2.739830026428688), (401.5554628854198, 1096.277077297115, 2.739830026428688), (400.6606215968277, 1096.657270729605, 2.739830026428688), (399.7657803082356, 1097.0374641620947, 2.739830026428688), (398.8709390196435, 1097.4176575945846, 2.739830026428688), (397.9760977310515, 1097.7978510270746, 2.739830026428688), (397.0812564424594, 1098.1780444595645, 2.739830026428688), (396.1864151538673, 1098.5582378920544, 2.739830026428688), (395.2915738652752, 1098.9384313245444, 2.739830026428688), (394.3967548911081, 1099.318677260896, 2.739492242286598), (393.5022271882191, 1099.69960782173, 2.738519982101022), (392.60807027168346, 1100.0814079160527, 2.737547721915446), (391.71428498673856, 1100.4640771829522, 2.7365754617298705)]
Given a query pose, you can also find the closest pose on a lane.
closest_pose_on_lane, distance_along_lane = arcline_path_utils.project_pose_to_lane((x, y, yaw), lane_record)
print(x, y, yaw)
closest_pose_on_lane
395 1095 0
(396.25524909914367, 1098.5289922434013, 2.739830026428688)
# Meters
distance_along_lane
27.5
To find the entire length of the lane, you can use the length_of_lane
function.
arcline_path_utils.length_of_lane(lane_record)
32.08455403942341
You can also compute the curvature of a lane at a given length along the lane.
# 0 means it is a straight lane
arcline_path_utils.get_curvature_at_distance_along_lane(distance_along_lane, lane_record)
0
Let's render a particular patch on the map:
my_patch = (300, 1000, 500, 1200)
fig, ax = nusc_map.render_map_patch(my_patch, nusc_map.non_geometric_layers, figsize=(10, 10), bitmap=bitmap)
A lot of layers can be seen in this patch. Lets retrieve all map records that are in this patch.
within
will return all non geometric records that are within the map patchintersect
will return all non geometric records that intersect the map patchrecords_within_patch = nusc_map.get_records_in_patch(my_patch, nusc_map.non_geometric_layers, mode='within')
records_intersect_patch = nusc_map.get_records_in_patch(my_patch, nusc_map.non_geometric_layers, mode='intersect')
Since there are a lot of records, we focus only on the layer road_segment
:
layer = 'road_segment'
print('Found %d records of %s (within).' % (len(records_within_patch[layer]), layer))
print('Found %d records of %s (intersect).' % (len(records_intersect_patch[layer]), layer))
Found 25 records of road_segment (within). Found 36 records of road_segment (intersect).
We see that using the option intersect
typically returns more records than within
.
Looking at the above plot. Point (390, 1100)
seems to be on a stop line. Lets verify that.
my_point = (390, 1100)
layers = nusc_map.layers_on_point(my_point[0], my_point[1])
assert len(layers['stop_line']) > 0, 'Error: No stop line found!'
Indeed, we see a stop_line
record.
To directly check for stop_line
records, we run:
nusc_map.record_on_point(my_point[0], my_point[1], 'stop_line')
'942dc2b1-345c-4fe7-83d0-9eeed8202709'
Let's look at the bounds/extremities of that record
nusc_map.get_bounds('stop_line', 'ac0a935f-99af-4dd4-95e3-71c92a5e58b1')
(751.928131680929, 920.9848298895206, 762.8608345788314, 929.439260149884)
Let us look more closely at the different map layers:
nusc_map.layer_names
['polygon', 'line', 'node', 'drivable_area', 'road_segment', 'road_block', 'lane', 'ped_crossing', 'walkway', 'stop_line', 'carpark_area', 'lane_connector', 'road_divider', 'lane_divider', 'traffic_light']
Our map database consists of multiple layers. Where each layer is made up of records. Each record will have a token identifier.
We see how our map layers are divided into two types of layers. One set of layer belong to the geometric_layers
group, another set of layers belongs to the non_geometric_layers
group.
geometric_layers
define geometric entities in the map:Line
record can consist of more than one line segment.non_geometric_layers
represent physical entities in the map. They can have more than one geometric representation (such as drivable_areas
), but must be strictly of one type (e.g. road_segment
, lane_divider
).nusc_map.geometric_layers
['polygon', 'line', 'node']
The most primitive geometric record in our map database. This is the only layer that explicitly contains spatial coordinates.
sample_node = nusc_map.node[0]
sample_node
{'token': '2163fdc8-77fc-4c1c-a099-70bc5be9f9b7', 'x': 994.6139837360693, 'y': 1054.5199816348131}
Defines a line sequence of one or more lines and therefore consists of two or more nodes.
sample_line = nusc_map.line[2]
sample_line
{'token': '19f89773-f466-4d21-a583-4a963e6fe042', 'node_tokens': ['ee2752d0-5fc9-495c-aa4b-fc24f703db1b', '48b2f4ea-9781-4cf2-82ff-624267be98d6', '9995a31d-089b-45f1-81ec-11925d17dbda']}
Defines a polygon which may contain holes.
Every polygon record comprises of a list of exterior nodes, and zero or more list(s) of nodes that constitute (zero or more) holes.
Let's look at one polygon record:
sample_polygon = nusc_map.polygon[3]
sample_polygon.keys()
dict_keys(['token', 'exterior_node_tokens', 'holes'])
sample_polygon['exterior_node_tokens'][:10]
['de837055-7009-42f2-80c7-cb224a9ce750', '86ee21c3-4a35-4f0e-9286-57b4cde9a2df', 'ac4be197-c315-4233-98e0-d52007091090', '3ae2328f-cf1d-4597-8cc6-c9ac9f28f3b5', '3bb30867-05e0-4687-bd67-613ad5ad6476', '507d041c-5a0a-439e-9fbe-e57556e02d93', '19b5ae73-163a-47a7-b6f6-deea88d8d72f', 'c0eedac8-f7d0-44d1-becc-535183fbf496', '9fe84337-f37d-4873-bd7b-be3922203a36', 'cb8ee715-d481-49d6-a6c7-c765afccdfd5']
sample_holes = sample_polygon['holes'][0]
sample_holes
{'node_tokens': ['13e0ec9d-e592-4d15-a30f-e61c5a04546f', 'ed06f702-2a3f-4c7e-b200-6c41d20f04c7', '8e7b8e2f-7218-4e00-bce3-1f79245f5946', '542f7094-634e-4972-9108-602184f81ec8', '45dd272a-cda0-4de5-89b3-28ff539881e7', 'c8952a38-8199-4580-b27c-ce7631f598cd', 'f3def455-f19a-4379-9903-71628c0f9303', '16083beb-d393-4045-b903-bbd9a126d0bc', '80879705-d6ec-4f52-b54a-859a13c2670c', '1980fcec-6ba3-4fb4-b3c1-0126886cc29f', '1c01e9ae-2974-4863-856d-56f6a472355a', '85feaeae-1802-44f2-90af-9e04ca5934ff', 'af88a07c-4aa6-479d-bc1e-7b9a824fc750', 'f9a9097e-e844-486f-a497-f3521dd6bf2c', '86f21780-6f2a-4cbe-8aac-f13a0b5adf3f', '35e8c5f7-b89d-494b-9840-725cd4fa6010', 'da77624e-765e-44f8-8374-c7513684f015', '28aa464f-93db-4ef1-a907-9abf07b5a380', '0e3ba3fd-3e85-4c26-bf20-d9144e5864cc', 'ab924ff2-c6fe-41c0-b8f4-dc9db5fc1a48']}
Every non-geometric layer is associated with at least one geometric object.
nusc_map.non_geometric_layers
['drivable_area', 'road_segment', 'road_block', 'lane', 'ped_crossing', 'walkway', 'stop_line', 'carpark_area', 'road_divider', 'lane_divider', 'traffic_light']
Drivable area is defined as the area where the car can drive, without consideration for driving directions or legal restrictions. This is the only layer in which the record can be represented by more than one geometric entity. Note: On some machines this polygon renders incorrectly as a filled black rectangle.
sample_drivable_area = nusc_map.drivable_area[0]
sample_drivable_area
{'token': 'c3e28556-b711-4581-9970-b66166fb907d', 'polygon_tokens': ['fff7b0c9-1eaf-4988-afe3-e4e4607f85e3', 'd235013d-2a07-4181-9862-c666b49a79b4', '0bbf311c-405d-433b-a097-7d9c292a9b87', 'b4dfb634-2721-42d9-aa5d-0f8ec9a2fa31', 'c4b4c925-6ddb-4e4b-a4ca-609e1ca626c2', 'a60970c7-86cd-4169-ae9a-b9b51e4ec950', '1209379e-bc10-4d65-9fb1-0ee938032130']}
fig, ax = nusc_map.render_record('drivable_area', sample_drivable_area['token'], other_layers=[])
A segment of road on a drivable area. It has an is_intersection
flag which denotes whether a particular road segment is an intersection.
It may or may not have an association with a drivable area
record from its drivable_area_token
field.
sample_road_segment = nusc_map.road_segment[600]
sample_road_segment
{'token': 'c366bb7b-1f3b-4840-b7d3-9d3362b02589', 'polygon_token': '254a099d-d884-4c5f-a444-d3703163f173', 'is_intersection': True, 'drivable_area_token': 'c3e28556-b711-4581-9970-b66166fb907d', 'exterior_node_tokens': ['15d4c84c-a459-492d-8fae-619c6eccb60c', '4e336b1e-b67c-4452-bad5-fedfb970fac4', '6060b6c9-26c8-4887-8b7d-0aa67404cd1a', '54305c13-60f8-4976-a555-8d915eb9ae4f', '6a2e3ae8-72c8-4605-a644-8c74b8454c98', 'f9190d61-9d7a-46cb-9f6d-909f51f7565a', 'eef9c998-204a-40f6-ad27-a600849e1b68', 'bfa79595-ab08-46b5-ae1a-c66c57ebbe9f', '439fc8a3-c175-4511-99bf-e993a016c280', 'bd2ca111-5da9-4e2d-b4c1-13cedb1f96ef', 'a95821b5-a97e-401c-b96c-938037a8fbb0', '10d9a934-338a-413b-8835-f8ae1d9abb87', '61372da3-bed1-4524-bca4-26cb2f4d0f8e', '4f639960-ad63-40e2-a58f-2e7387a5c846'], 'holes': []}
As observed, for all non geometric objects except drivable_area
, we provide a shortcut to its nodes
.
Let's take a look at a road_segment
record with is_intersection == True
sample_intersection_road_segment = nusc_map.road_segment[3]
sample_intersection_road_segment
{'token': '00cbbc19-252e-4eef-a9e9-3158446bd794', 'polygon_token': 'c6df6bdd-698c-40b2-b2a0-728eb5172efa', 'is_intersection': True, 'drivable_area_token': 'c3e28556-b711-4581-9970-b66166fb907d', 'exterior_node_tokens': ['a29ee8f6-53a5-44c3-878f-5137e06b343d', '4d518646-6a49-4bad-96c8-e37af381a189', '6958b257-2443-4366-afb2-cfb9585e756b', 'debfdfe0-d701-4833-ada6-ec8dd1d612b4', 'c92b7476-10ac-4222-b5c0-f0512aca89b9', 'd261ca11-b827-4cc2-ab34-092970b7d6fa', '3df5c6fc-92e5-40f2-bacf-6322f4896495', '8007e1bd-3ed6-4fab-8530-5717cfb93fc9', 'cc8cf624-d4e1-4fed-a35a-d27ff7b3e4e9', '067e77f2-7443-46b1-a7e4-3ce0af7501a5', 'a918f42d-5f99-477a-ad8f-027e1af656d8', '6063aace-dbc6-4761-a40d-e593d34ae8e6'], 'holes': []}
If we render this road segment we can see that it is indeed an intersection:
fig, ax = nusc_map.render_record('road_segment', sample_intersection_road_segment['token'], other_layers=[])
Road blocks are blocks of a road that have the same traffic direction. Multiple road blocks are grouped in a road segment.
Within a road block, the number of lanes is consistent.
sample_road_block = nusc_map.road_block[0]
sample_road_block
{'token': '002d8233-c9bf-4a9b-9d53-be86cd6cf73f', 'polygon_token': '29fc4c78-75ae-4777-adab-f33d93591661', 'from_edge_line_token': 'b0d2163e-732b-4be6-b6f7-2add8b4c7e8f', 'to_edge_line_token': '7ce97362-1133-4c19-a73c-5cfa8f0d64f0', 'road_segment_token': '85a06614-958c-461f-bc11-6cadd68efa7d', 'exterior_node_tokens': ['46cf43f6-30ea-437e-83b3-42af3ce2783b', 'aca16135-79a1-4acd-a68f-3918c38d54be', 'ce31539b-d8c8-45a0-94df-3ac3a585225b', '26704699-79a6-4d4c-8ca2-d65ffb3ac11b', '2d0168af-7952-416d-8aff-7512130fb73d', 'e3fa777d-d87a-45f9-bd41-5364e3bb9dd2', 'bedec7db-1f55-4639-9826-ab8639ee250b', '05243627-6e25-472d-af1f-aca0ff30b00c'], 'holes': []}
Every road block has a from_edge_line_token
and to_edge_line_token
that denotes its traffic direction.
fig, ax = nusc_map.render_record('road_block', sample_road_block['token'], other_layers=[])
Lanes are parts of the road where vehicles drive in a single direction.
sample_lane_record = nusc_map.lane[600]
sample_lane_record
{'token': 'a6f12a5c-f6fa-4e99-993f-4cbd6f982c65', 'polygon_token': 'd50a64b4-021c-4f73-8496-f6491eb0d3fa', 'lane_type': 'CAR', 'from_edge_line_token': '32f811fd-a2d8-4dc8-9785-8c43d0ea947c', 'to_edge_line_token': 'ca27a4ad-37ca-44b7-8703-85aa39119a47', 'left_lane_divider_segments': [], 'right_lane_divider_segments': [], 'exterior_node_tokens': ['124f5c61-f391-43f0-a245-32a325243a73', '55ad1d37-fe95-4e5c-a43e-1148ad4a13f6', 'e3df7273-cb2e-4fef-8849-72141d549a1c', '9b5764b9-ca40-4622-afec-494d979b716a', '1066e47d-486e-45cf-affe-59c4e4e93fa9', '741bede3-d6c2-44c0-966f-fdce30f57817', 'f5f4e292-056a-499b-b097-2e70e07435a7', 'bbdf380c-9aed-4082-88e5-834eb39bca9e', 'a040018c-3f38-4779-8876-6741b4aa4f81', '0d110059-c96f-413d-afd9-65963d4823fd', '1d0feda2-ee54-4ebd-aaa1-7c669089b4ef', '445a42dc-dbac-4fea-b03d-ece94729d0e8', 'd8f8d28e-8be1-4c8a-a008-6c852b86363b'], 'holes': [], 'left_lane_divider_segment_nodes': [], 'right_lane_divider_segment_nodes': []}
Aside from the token and the geometric representation, a lane has several fields:
lane_type
denotes whether cars or bikes are allowed to navigate through that lane.from_edge_line_token
and to_edge_line_token
denotes their traffic direction.left_lane_divider_segments
and right_lane_divider_segment
denotes their lane dividers.left_lane_divider_segment_nodes
and right_lane_divider_segment_nodes
denotes the nodes that makes up the lane dividers.fig, ax = nusc_map.render_record('lane', sample_lane_record['token'], other_layers=[])
Pedestrian crossings are regions where pedestrians can legally cross the road, typically highlighted by white markings. Each pedestrian crossing record has to be on a road segment. It has the road_segment_token
field which denotes the road_segment
record it is associated with.
sample_ped_crossing_record = nusc_map.ped_crossing[0]
sample_ped_crossing_record
{'token': '027c4ccd-56c9-4980-9949-1d42bb36f23c', 'polygon_token': '62138b18-6dd1-4c1e-8f11-7a2c8d5783c8', 'road_segment_token': 'af7744d2-6dfe-4b9f-ab9a-58cc155f3f08', 'exterior_node_tokens': ['58cf4a19-d28e-44b1-b4c0-bc217e50da1e', '0e3fda05-0936-4cbb-acbd-fc582750b3d3', '6a0f7286-8e6d-4fb5-b874-c830f090a05a', '0f45b051-0f14-469d-bde3-e8975b4d67cb'], 'holes': []}
fig, ax = nusc_map.render_record('ped_crossing', sample_ped_crossing_record['token'])
A walkway or sidewalk is the typically elevated area next to a road where pedestrians are protected from vehicles on the road.
sample_walkway_record = nusc_map.walkway[0]
sample_walkway_record
{'token': '00a01743-8d10-41ca-849e-ef6a32bee77d', 'polygon_token': '17ff2a4b-a5c2-41d2-abf5-4a8aa07cb30f', 'exterior_node_tokens': ['e7aa76d5-8368-4749-900d-dd2cbb4971e6', 'c7187b86-fdb8-4eec-ba71-0f2c6ee0b57b', '8bd36561-55ef-4ff6-ab55-583dc59f2b73', '47db713d-fc9f-49bd-b5ba-6d89123f6357', '442e2766-733f-4147-b1cf-4238de3b93e1', '5a831f39-0352-4fcf-ab76-e696c9d5e651', 'ac7839a1-73ef-4f39-80f0-e32ee2d816ae', '4434e104-1317-4bcd-bddf-ac0abb4e158c', '1cc537c7-1b78-443a-8513-8894cb807c8a', '85cff4b3-a56b-45e5-8e6b-880a73860696', '9344380b-375f-480f-9877-aa75e21b7acd', '6c5a6416-ab0c-4221-842a-bc5aa97da61b', '60e66d85-c5c1-4d27-8d67-d5ce28c2dac1', '68c442df-c38f-482e-b863-10afae9c69ce', '519240d4-5c8c-45e6-8d85-5ec78eac43bf', 'f12f278c-e0ca-4c18-ab14-d6b259885687', '95e6e737-310d-4a9a-99aa-02dc4365ff19', 'f69e2a9d-f43b-4a3d-834b-bc0de489caf5'], 'holes': []}
fig, ax = nusc_map.render_record('walkway', sample_walkway_record['token'])
The physical world's stop line, even though the name implies that it should possess a line
geometric representation, in reality its physical representation is an area where the ego vehicle must stop.
sample_stop_line_record = nusc_map.stop_line[1]
sample_stop_line_record
{'token': '00904b8f-3166-47b8-9cbb-30062caec0eb', 'polygon_token': '90102f73-9921-4d2a-8e07-148503868957', 'stop_line_type': 'TURN_STOP', 'ped_crossing_tokens': ['96748923-eabf-4142-8458-92ff580e997f'], 'traffic_light_tokens': [], 'road_block_token': '', 'exterior_node_tokens': ['a3e110de-2443-406f-bf54-ef9b4dc46939', 'e5d038c8-f964-4ae2-b498-9952496c801f', 'bbec1377-0e20-4888-9f79-2a1aa50b3b88', '37a078fa-2804-412e-b8b9-682fe21ad8be', '50597561-e04f-4ea1-894a-cfd2c212aef0', 'b05b2d23-3a12-493d-9d8d-e57f4f8ddc60'], 'holes': [], 'cue': [{'token': '96748923-eabf-4142-8458-92ff580e997f', 'polygon_token': 'f8a39c38-1d04-4dc0-9e35-f63966e56250', 'road_segment_token': '6ea9d0a6-65e7-4038-ae50-4fb89a4c296d', 'exterior_node_tokens': ['7931be00-b6a7-437d-9335-e4314dbe47b4', '1f6f7c4a-27a2-4a18-96bd-fe597546440f', 'a28f6633-a23e-44f6-8355-0c06df42005e', '235431b5-9f71-452d-a3b2-bdeaaa44aa41'], 'holes': []}]}
It has several attributes:
stop_line_type
, the type of the stop line, this represents the reasons why the ego vehicle would stop ped_crossing_tokens
denotes the association information if the stop_line_type
is PED_CROSSING
.traffic_light_tokens
denotes the association information if the stop_line_type
is TRAFFIC_LIGHT
.road_block_token
denotes the association information to a road_block
, can be empty by default. cues
field contains the reason on why this this record is a stop_line
. An area can be a stop line due to multiple reasons:stop_line_type
of "PED_CROSSING" or "TURN_STOP" are ped_crossing
records.stop_line_type
of TRAFFIC_LIGHT" are traffic_light
records.stop_line_type
of "STOP_SIGN" or "YIELD".fig, ax = nusc_map.render_record('stop_line', sample_stop_line_record['token'])
A car park or parking lot area.
sample_carpark_area_record = nusc_map.carpark_area[1]
sample_carpark_area_record
{'token': '0a711883-2477-4eb5-aef8-cc9ad3e3158a', 'polygon_token': 'eca315c8-cfb7-4759-a91a-d148d08ef2eb', 'orientation': 2.5073506567369885, 'road_block_token': '2b60cc1b-0882-4ef3-8207-f7cb3561aff9', 'exterior_node_tokens': ['0043375d-b853-4149-94a5-3ca6c984e3d8', '5aa572e1-1848-4739-bbd8-f5934fb3e1ea', '5419cf3e-9e02-4683-adae-fe0dcd948644', 'ba9efc27-c461-402f-a172-e451e92ef7c8'], 'holes': []}
It has several attributes:
orientation
denotes the direction of parked cars in radians.road_block_token
denotes the association information to a road_block
.fig, ax = nusc_map.render_record('carpark_area', sample_carpark_area_record['token'])
A divider that separates one road block from another.
sample_road_divider_record = nusc_map.road_divider[0]
sample_road_divider_record
{'token': '00bbfc65-0b44-4b4c-b517-6d87dc02529c', 'line_token': '98c91318-5854-41ac-9210-001b57b8185f', 'road_segment_token': 'b1ed2f76-bfcd-4b0c-b367-7a20cf707b95', 'node_tokens': ['4e2605d4-b9f4-41f9-a03c-032c8d4a3c24', '1cbbdda6-5ee6-4b4d-8bcc-30af18094978']}
road_segment_token
saves the association information to a road_segment
.
fig, ax = nusc_map.render_record('road_divider', sample_road_divider_record['token'])
A lane divider comes between lanes that point in the same traffic direction.
sample_lane_divider_record = nusc_map.lane_divider[0]
sample_lane_divider_record
{'token': '00569b72-a7dc-4cdf-9bf3-7f3583c6dbae', 'line_token': '9ac741dc-20b5-44f3-9f0a-41e371a722ee', 'lane_divider_segments': [{'node_token': '57d546eb-682c-4540-871c-2e8d6a67f2de', 'segment_type': 'DOUBLE_DASHED_WHITE'}, {'node_token': 'fef2c634-7096-4b48-bf87-6575d2a67b56', 'segment_type': 'DOUBLE_DASHED_WHITE'}, {'node_token': '153990f1-b0da-4243-a065-e4a99d29e180', 'segment_type': 'DOUBLE_DASHED_WHITE'}, {'node_token': '8ad3000f-c1e9-4eda-8bf1-c5f64a879c54', 'segment_type': 'NIL'}], 'node_tokens': ['57d546eb-682c-4540-871c-2e8d6a67f2de', 'fef2c634-7096-4b48-bf87-6575d2a67b56', '153990f1-b0da-4243-a065-e4a99d29e180', '8ad3000f-c1e9-4eda-8bf1-c5f64a879c54']}
The lane_divider_segments
field consist of different node
s and their respective segment_type
s which denotes their physical appearance.
fig, ax = nusc_map.render_record('lane_divider', sample_lane_divider_record['token'])
A physical world's traffic light.
sample_traffic_light_record = nusc_map.traffic_light[0]
sample_traffic_light_record
{'token': '00590fed-3542-4c20-9927-f822134be5fc', 'line_token': '5bffb006-bce8-44a4-a466-5580f1d748fd', 'traffic_light_type': 'VERTICAL', 'from_road_block_token': '71c79c48-819c-4b17-ad28-2a9e82ba1596', 'items': [{'color': 'RED', 'shape': 'CIRCLE', 'rel_pos': {'tx': 0.0, 'ty': 0.0, 'tz': 0.632, 'rx': 0.0, 'ry': 0.0, 'rz': 0.0}, 'to_road_block_tokens': []}, {'color': 'YELLOW', 'shape': 'CIRCLE', 'rel_pos': {'tx': 0.0, 'ty': 0.0, 'tz': 0.381, 'rx': 0.0, 'ry': 0.0, 'rz': 0.0}, 'to_road_block_tokens': []}, {'color': 'GREEN', 'shape': 'CIRCLE', 'rel_pos': {'tx': 0.0, 'ty': 0.0, 'tz': 0.13, 'rx': 0.0, 'ry': 0.0, 'rz': 0.0}, 'to_road_block_tokens': []}, {'color': 'GREEN', 'shape': 'RIGHT', 'rel_pos': {'tx': 0.0, 'ty': -0.26, 'tz': 0.13, 'rx': 0.0, 'ry': 0.0, 'rz': 0.0}, 'to_road_block_tokens': ['bd26d490-8822-469b-ae60-74f6c0c9e1cb']}], 'pose': {'tx': 369.2207339994191, 'ty': 1129.3945093980494, 'tz': 2.4, 'rx': 0.0, 'ry': 0.0, 'rz': -0.6004778487509836}, 'node_tokens': ['8e483ef5-75e5-417a-bc78-fa7750297fb1', '78a4b686-3207-48fa-ae2a-d5f875e0ee37']}
It has several attributes:
traffic_light_type
denotes whether the traffic light is oriented horizontally or vertically.from_road_block_tokens
denotes from which road block the traffic light guides.items
are the bulbs for that traffic light.pose
denotes the pose of the traffic light.Let's examine the items
field
sample_traffic_light_record['items']
[{'color': 'RED', 'shape': 'CIRCLE', 'rel_pos': {'tx': 0.0, 'ty': 0.0, 'tz': 0.632, 'rx': 0.0, 'ry': 0.0, 'rz': 0.0}, 'to_road_block_tokens': []}, {'color': 'YELLOW', 'shape': 'CIRCLE', 'rel_pos': {'tx': 0.0, 'ty': 0.0, 'tz': 0.381, 'rx': 0.0, 'ry': 0.0, 'rz': 0.0}, 'to_road_block_tokens': []}, {'color': 'GREEN', 'shape': 'CIRCLE', 'rel_pos': {'tx': 0.0, 'ty': 0.0, 'tz': 0.13, 'rx': 0.0, 'ry': 0.0, 'rz': 0.0}, 'to_road_block_tokens': []}, {'color': 'GREEN', 'shape': 'RIGHT', 'rel_pos': {'tx': 0.0, 'ty': -0.26, 'tz': 0.13, 'rx': 0.0, 'ry': 0.0, 'rz': 0.0}, 'to_road_block_tokens': ['bd26d490-8822-469b-ae60-74f6c0c9e1cb']}]
As mentioned, every entry in the items
field is a traffic light bulb. It has the color
information, the shape
information, rel_pos
which is the relative position, and the to_road_block_tokens
that denotes to which road blocks the traffic light bulb is guiding.