More info (#28)
* boundary to exterior * rename copy to cp, avoiding bugs * add connectivity and sidewalk/cross for nuscenes * update lane type * add semantic renderer * restore * nuplan works * format
This commit is contained in:
@@ -130,7 +130,7 @@ More operations and details is available at :ref:`operations`.
|
||||
The database can be loaded to MetaDrive simulator for scenario replay or closed-loop simulation.
|
||||
First of all, let's replay scenarios in the ``exp_converted`` database::
|
||||
|
||||
python -m scenarionet.sim -d /path/to/exp_converted
|
||||
python -m scenarionet.sim -d /path/to/exp_converted --render 2D
|
||||
|
||||
|
||||
By adding ``--render 3D`` flag, we can use 3D renderer::
|
||||
|
||||
@@ -267,7 +267,7 @@ When ``--remove_source`` is added, this ``copy`` command will be changed to ``mo
|
||||
|
||||
.. code-block:: text
|
||||
|
||||
python -m scenarionet.copy [-h] --from FROM --to TO [--remove_source] [--copy_raw_data]
|
||||
python -m scenarionet.cp [-h] --from FROM --to TO [--remove_source] [--copy_raw_data]
|
||||
[--exist_ok] [--overwrite]
|
||||
|
||||
Move or Copy an existing database
|
||||
@@ -395,7 +395,7 @@ please check Section :ref:`simulation` or the `MetaDrive document <https://metad
|
||||
.. code-block:: text
|
||||
|
||||
python -m scenarionet.sim [-h] --database_path DATABASE_PATH
|
||||
[--render {none,2D,3D,advanced}]
|
||||
[--render {none,2D,3D,advanced,semantic}]
|
||||
[--scenario_index SCENARIO_INDEX]
|
||||
|
||||
Load a database to simulator and replay scenarios
|
||||
@@ -404,7 +404,7 @@ please check Section :ref:`simulation` or the `MetaDrive document <https://metad
|
||||
-h, --help show this help message and exit
|
||||
--database_path DATABASE_PATH, -d DATABASE_PATH
|
||||
The path of the database
|
||||
--render {none,2D,3D,advanced}
|
||||
--render {none,2D,3D,advanced,semantic}
|
||||
--scenario_index SCENARIO_INDEX
|
||||
Specifying a scenario to run
|
||||
|
||||
|
||||
@@ -206,11 +206,12 @@ def extract_map_features(map_api, center, radius=500):
|
||||
block_polygons = []
|
||||
for layer in [SemanticMapLayer.ROADBLOCK, SemanticMapLayer.ROADBLOCK_CONNECTOR]:
|
||||
for block in nearest_vector_map[layer]:
|
||||
for lane_meta_data in block.interior_edges:
|
||||
edges = sorted(block.interior_edges, key=lambda lane: lane.index) \
|
||||
if layer == SemanticMapLayer.ROADBLOCK else block.interior_edges
|
||||
for index, lane_meta_data in enumerate(edges):
|
||||
if not hasattr(lane_meta_data, "baseline_path"):
|
||||
continue
|
||||
if isinstance(lane_meta_data.polygon.boundary, MultiLineString):
|
||||
# logger.warning("Stop using boundaries! Use exterior instead!")
|
||||
boundary = gpd.GeoSeries(lane_meta_data.polygon.boundary).explode(index_parts=True)
|
||||
sizes = []
|
||||
for idx, polygon in enumerate(boundary[0]):
|
||||
@@ -220,9 +221,20 @@ def extract_map_features(map_api, center, radius=500):
|
||||
points = lane_meta_data.polygon.boundary.xy
|
||||
polygon = [[points[0][i], points[1][i]] for i in range(len(points[0]))]
|
||||
polygon = nuplan_to_metadrive_vector(polygon, nuplan_center=[center[0], center[1]])
|
||||
|
||||
# According to the map attributes, lanes are numbered left to right with smaller indices being on the
|
||||
# left and larger indices being on the right.
|
||||
# @ See NuPlanLane.adjacent_edges()
|
||||
ret[lane_meta_data.id] = {
|
||||
SD.TYPE: MetaDriveType.LANE_SURFACE_STREET,
|
||||
SD.TYPE: MetaDriveType.LANE_SURFACE_STREET \
|
||||
if layer == SemanticMapLayer.ROADBLOCK else MetaDriveType.LANE_SURFACE_UNSTRUCTURE,
|
||||
SD.POLYLINE: extract_centerline(lane_meta_data, center),
|
||||
SD.ENTRY: [edge.id for edge in lane_meta_data.incoming_edges],
|
||||
SD.EXIT: [edge.id for edge in lane_meta_data.outgoing_edges],
|
||||
SD.LEFT_NEIGHBORS: [edge.id for edge in block.interior_edges[:index]] \
|
||||
if layer == SemanticMapLayer.ROADBLOCK else [],
|
||||
SD.RIGHT_NEIGHBORS: [edge.id for edge in block.interior_edges[index + 1:]] \
|
||||
if layer == SemanticMapLayer.ROADBLOCK else [],
|
||||
SD.POLYGON: polygon
|
||||
}
|
||||
if layer == SemanticMapLayer.ROADBLOCK_CONNECTOR:
|
||||
@@ -238,8 +250,41 @@ def extract_map_features(map_api, center, radius=500):
|
||||
if layer == SemanticMapLayer.ROADBLOCK:
|
||||
block_polygons.append(block.polygon)
|
||||
|
||||
# walkway
|
||||
for area in nearest_vector_map[SemanticMapLayer.WALKWAYS]:
|
||||
if isinstance(area.polygon.exterior, MultiLineString):
|
||||
boundary = gpd.GeoSeries(area.polygon.exterior).explode(index_parts=True)
|
||||
sizes = []
|
||||
for idx, polygon in enumerate(boundary[0]):
|
||||
sizes.append(len(polygon.xy[1]))
|
||||
points = boundary[0][np.argmax(sizes)].xy
|
||||
elif isinstance(area.polygon.exterior, LineString):
|
||||
points = area.polygon.exterior.xy
|
||||
polygon = [[points[0][i], points[1][i]] for i in range(len(points[0]))]
|
||||
polygon = nuplan_to_metadrive_vector(polygon, nuplan_center=[center[0], center[1]])
|
||||
ret[area.id] = {
|
||||
SD.TYPE: MetaDriveType.BOUNDARY_SIDEWALK,
|
||||
SD.POLYGON: polygon,
|
||||
}
|
||||
|
||||
# corsswalk
|
||||
for area in nearest_vector_map[SemanticMapLayer.CROSSWALK]:
|
||||
if isinstance(area.polygon.exterior, MultiLineString):
|
||||
boundary = gpd.GeoSeries(area.polygon.exterior).explode(index_parts=True)
|
||||
sizes = []
|
||||
for idx, polygon in enumerate(boundary[0]):
|
||||
sizes.append(len(polygon.xy[1]))
|
||||
points = boundary[0][np.argmax(sizes)].xy
|
||||
elif isinstance(area.polygon.exterior, LineString):
|
||||
points = area.polygon.exterior.xy
|
||||
polygon = [[points[0][i], points[1][i]] for i in range(len(points[0]))]
|
||||
polygon = nuplan_to_metadrive_vector(polygon, nuplan_center=[center[0], center[1]])
|
||||
ret[area.id] = {
|
||||
SD.TYPE: MetaDriveType.CROSSWALK,
|
||||
SD.POLYGON: polygon,
|
||||
}
|
||||
|
||||
interpolygons = [block.polygon for block in nearest_vector_map[SemanticMapLayer.INTERSECTION]]
|
||||
# logger.warning("Stop using boundaries! Use exterior instead!")
|
||||
boundaries = gpd.GeoSeries(unary_union(interpolygons + block_polygons)).boundary.explode(index_parts=True)
|
||||
# boundaries.plot()
|
||||
# plt.show()
|
||||
|
||||
@@ -219,7 +219,7 @@ def get_tracks_from_frames(nuscenes: NuScenes, scene_info, frames, num_to_interp
|
||||
max_vel = np.max(np.linalg.norm(interpolate_tracks[id]["state"]["velocity"], axis=-1))
|
||||
assert max_vel < 50, "Abnormal velocity!"
|
||||
if max_vel > 30:
|
||||
print("\nWARNING: Too large peed for {}: {}".format(id, max_vel))
|
||||
print("\nWARNING: Too large speed for {}: {}".format(id, max_vel))
|
||||
|
||||
# heading
|
||||
# then update position
|
||||
@@ -273,8 +273,8 @@ def get_map_features(scene_info, nuscenes: NuScenes, map_center, radius=500, poi
|
||||
'road_segment',
|
||||
'road_block',
|
||||
'lane',
|
||||
# 'ped_crossing',
|
||||
# 'walkway',
|
||||
'ped_crossing',
|
||||
'walkway',
|
||||
# 'stop_line',
|
||||
# 'carpark_area',
|
||||
'lane_connector',
|
||||
@@ -282,6 +282,8 @@ def get_map_features(scene_info, nuscenes: NuScenes, map_center, radius=500, poi
|
||||
'lane_divider',
|
||||
'traffic_light'
|
||||
]
|
||||
# road segment includes all roadblocks (a list of lanes in the same direction), intersection and unstructured road
|
||||
|
||||
map_objs = map_api.get_records_in_radius(map_center[0], map_center[1], radius, layer_names)
|
||||
|
||||
# build map boundary
|
||||
@@ -303,7 +305,6 @@ def get_map_features(scene_info, nuscenes: NuScenes, map_center, radius=500, poi
|
||||
polygon = map_api.extract_polygon(seg_info["polygon_token"])
|
||||
polygons.append(polygon)
|
||||
polygons = [geom if geom.is_valid else geom.buffer(0) for geom in polygons]
|
||||
# logger.warning("Stop using boundaries! Use exterior instead!")
|
||||
boundaries = gpd.GeoSeries(unary_union(polygons)).boundary.explode(index_parts=True)
|
||||
for idx, boundary in enumerate(boundaries[0]):
|
||||
block_points = np.array(list(i for i in zip(boundary.coords.xy[0], boundary.coords.xy[1])))
|
||||
@@ -313,6 +314,7 @@ def get_map_features(scene_info, nuscenes: NuScenes, map_center, radius=500, poi
|
||||
SD.POLYLINE: block_points - np.asarray(map_center)[:2]
|
||||
}
|
||||
|
||||
# broken line
|
||||
for id in map_objs["lane_divider"]:
|
||||
line_info = map_api.get("lane_divider", id)
|
||||
assert line_info["token"] == id
|
||||
@@ -320,6 +322,7 @@ def get_map_features(scene_info, nuscenes: NuScenes, map_center, radius=500, poi
|
||||
line = np.asarray([[line[0][i], line[1][i]] for i in range(len(line[0]))])
|
||||
ret[id] = {SD.TYPE: MetaDriveType.LINE_BROKEN_SINGLE_WHITE, SD.POLYLINE: line - np.asarray(map_center)[:2]}
|
||||
|
||||
# solid line
|
||||
for id in map_objs["road_divider"]:
|
||||
line_info = map_api.get("road_divider", id)
|
||||
assert line_info["token"] == id
|
||||
@@ -327,6 +330,7 @@ def get_map_features(scene_info, nuscenes: NuScenes, map_center, radius=500, poi
|
||||
line = np.asarray([[line[0][i], line[1][i]] for i in range(len(line[0]))])
|
||||
ret[id] = {SD.TYPE: MetaDriveType.LINE_SOLID_SINGLE_YELLOW, SD.POLYLINE: line - np.asarray(map_center)[:2]}
|
||||
|
||||
# normal lane
|
||||
for id in map_objs["lane"]:
|
||||
lane_info = map_api.get("lane", id)
|
||||
assert lane_info["token"] == id
|
||||
@@ -338,8 +342,13 @@ def get_map_features(scene_info, nuscenes: NuScenes, map_center, radius=500, poi
|
||||
SD.POLYLINE: np.asarray(discretize_lane(map_api.arcline_path_3[id], resolution_meters=points_distance)) -
|
||||
np.asarray(map_center),
|
||||
SD.POLYGON: boundary_polygon - np.asarray(map_center)[:2],
|
||||
SD.ENTRY: map_api.get_incoming_lane_ids(id),
|
||||
SD.EXIT: map_api.get_outgoing_lane_ids(id),
|
||||
SD.LEFT_NEIGHBORS: [],
|
||||
SD.RIGHT_NEIGHBORS: [],
|
||||
}
|
||||
|
||||
# intersection lane
|
||||
for id in map_objs["lane_connector"]:
|
||||
lane_info = map_api.get("lane_connector", id)
|
||||
assert lane_info["token"] == id
|
||||
@@ -347,13 +356,51 @@ def get_map_features(scene_info, nuscenes: NuScenes, map_center, radius=500, poi
|
||||
# boundary_polygon = [[boundary[0][i], boundary[1][i], 0.1] for i in range(len(boundary[0]))]
|
||||
# boundary_polygon += [[boundary[0][i], boundary[1][i], 0.] for i in range(len(boundary[0]))]
|
||||
ret[id] = {
|
||||
SD.TYPE: MetaDriveType.LANE_SURFACE_STREET,
|
||||
SD.TYPE: MetaDriveType.LANE_SURFACE_UNSTRUCTURE,
|
||||
SD.POLYLINE: np.asarray(discretize_lane(map_api.arcline_path_3[id], resolution_meters=points_distance)) -
|
||||
np.asarray(map_center),
|
||||
# SD.POLYGON: boundary_polygon,
|
||||
"speed_limit_kmh": 100
|
||||
"speed_limit_kmh": 100,
|
||||
SD.ENTRY: map_api.get_incoming_lane_ids(id),
|
||||
SD.EXIT: map_api.get_outgoing_lane_ids(id)
|
||||
}
|
||||
|
||||
# crosswalk
|
||||
for id in map_objs["ped_crossing"]:
|
||||
info = map_api.get("ped_crossing", id)
|
||||
assert info["token"] == id
|
||||
boundary = map_api.extract_polygon(info["polygon_token"]).exterior.xy
|
||||
boundary_polygon = np.asarray([[boundary[0][i], boundary[1][i]] for i in range(len(boundary[0]))])
|
||||
ret[id] = {
|
||||
SD.TYPE: MetaDriveType.CROSSWALK,
|
||||
SD.POLYGON: boundary_polygon - np.asarray(map_center)[:2],
|
||||
}
|
||||
|
||||
# walkway
|
||||
for id in map_objs["walkway"]:
|
||||
info = map_api.get("walkway", id)
|
||||
assert info["token"] == id
|
||||
boundary = map_api.extract_polygon(info["polygon_token"]).exterior.xy
|
||||
boundary_polygon = np.asarray([[boundary[0][i], boundary[1][i]] for i in range(len(boundary[0]))])
|
||||
ret[id] = {
|
||||
SD.TYPE: MetaDriveType.BOUNDARY_SIDEWALK,
|
||||
SD.POLYGON: boundary_polygon - np.asarray(map_center)[:2],
|
||||
}
|
||||
|
||||
# # stop_line
|
||||
# for id in map_objs["stop_line"]:
|
||||
# info = map_api.get("stop_line", id)
|
||||
# assert info["token"] == id
|
||||
# boundary = map_api.extract_polygon(info["polygon_token"]).exterior.xy
|
||||
# boundary_polygon = np.asarray([[boundary[0][i], boundary[1][i]] for i in range(len(boundary[0]))])
|
||||
# ret[id] = {
|
||||
# SD.TYPE: MetaDriveType.STOP_LINE,
|
||||
# SD.POLYGON: boundary_polygon - np.asarray(map_center)[:2],
|
||||
# }
|
||||
|
||||
# 'stop_line',
|
||||
# 'carpark_area',
|
||||
|
||||
return ret
|
||||
|
||||
|
||||
|
||||
@@ -18,7 +18,7 @@ class WaymoLaneType:
|
||||
LANE_BIKE_LANE = 3
|
||||
|
||||
ENUM_TO_STR = {
|
||||
UNKNOWN: 'UNKNOWN',
|
||||
UNKNOWN: 'LANE_UNKNOWN',
|
||||
LANE_FREEWAY: 'LANE_FREEWAY',
|
||||
LANE_SURFACE_STREET: 'LANE_SURFACE_STREET',
|
||||
LANE_BIKE_LANE: 'LANE_BIKE_LANE'
|
||||
|
||||
@@ -12,7 +12,7 @@ if __name__ == '__main__':
|
||||
|
||||
parser = argparse.ArgumentParser(description=desc)
|
||||
parser.add_argument("--database_path", "-d", required=True, help="The path of the database")
|
||||
parser.add_argument("--render", default="none", choices=["none", "2D", "3D", "advanced"])
|
||||
parser.add_argument("--render", default="none", choices=["none", "2D", "3D", "advanced", "semantic"])
|
||||
parser.add_argument("--scenario_index", default=None, type=int, help="Specifying a scenario to run")
|
||||
args = parser.parse_args()
|
||||
|
||||
@@ -48,7 +48,7 @@ if __name__ == '__main__':
|
||||
"data_directory": database_path,
|
||||
}
|
||||
)
|
||||
for index in range(2, num_scenario if args.scenario_index is not None else 1000000):
|
||||
for index in range(0, num_scenario if args.scenario_index is not None else 1000000):
|
||||
env.reset(seed=index if args.scenario_index is None else args.scenario_index)
|
||||
for t in range(10000):
|
||||
env.step([0, 0])
|
||||
@@ -62,9 +62,10 @@ if __name__ == '__main__':
|
||||
}
|
||||
)
|
||||
|
||||
if args.render == "2D":
|
||||
if args.render == "2D" or args.render == "semantic":
|
||||
env.render(
|
||||
film_size=(3000, 3000),
|
||||
semantic_map=args.render == "semantic",
|
||||
target_vehicle_heading_up=False,
|
||||
mode="top_down",
|
||||
text={
|
||||
|
||||
Reference in New Issue
Block a user