From 48bcb8f62066d0f1cc63d324dc54e88018918543 Mon Sep 17 00:00:00 2001 From: Saul Field Date: Tue, 8 Nov 2022 17:09:59 -0500 Subject: [PATCH 01/19] Implement partial build and caching for scenarios --- .gitignore | 1 + smarts/core/utils/file.py | 17 ++ smarts/sstudio/genscenario.py | 264 ++++++++++++++++++------ smarts/sstudio/scenario_construction.py | 1 + smarts/sstudio/types.py | 24 +-- 5 files changed, 225 insertions(+), 82 deletions(-) diff --git a/.gitignore b/.gitignore index fd3e4e9c7d..ae335296cf 100644 --- a/.gitignore +++ b/.gitignore @@ -108,6 +108,7 @@ shifted_map-AUTOGEN.net.xml *.pkl *.shf *.tfrecord* +build.db # Manually generated sumo route files !zoo/evaluation/scenarios/**/traffic/*.rou.xml diff --git a/smarts/core/utils/file.py b/smarts/core/utils/file.py index 9251b9c8ea..72d5f554dd 100644 --- a/smarts/core/utils/file.py +++ b/smarts/core/utils/file.py @@ -17,9 +17,11 @@ # LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, # OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN # THE SOFTWARE. +from ctypes import c_int64 import dataclasses import hashlib import os +import pickle import shutil import struct from contextlib import contextmanager @@ -109,6 +111,21 @@ def file_md5_hash(file_path: str) -> str: return str(hasher.hexdigest()) +def pickle_hash(obj) -> str: + """Converts a Python object to a hash value. NOTE: NOT stable across different Python versions.""" + pickle_bytes = pickle.dumps(obj, protocol=4) + hasher = hashlib.md5() + hasher.update(pickle_bytes) + return hasher.hexdigest() + + +def pickle_hash_int(obj) -> int: + """Converts a Python object to a hash value. NOTE: NOT stable across different Python versions.""" + hash_str = pickle_hash(obj) + val = int(hash_str, 16) + return c_int64(val).value + + def smarts_log_dir() -> str: """Retrieves the smarts logging directory.""" ## Following should work for linux and macos diff --git a/smarts/sstudio/genscenario.py b/smarts/sstudio/genscenario.py index 0a02b0032a..9aaf7d4633 100644 --- a/smarts/sstudio/genscenario.py +++ b/smarts/sstudio/genscenario.py @@ -26,14 +26,16 @@ import logging import os import pickle -import subprocess -import sys +import sqlite3 from dataclasses import replace from pathlib import Path -from typing import Any, Optional, Sequence, Tuple, Union +from typing import Any, Dict, List, Optional, Sequence, Tuple, Union import cloudpickle +from smarts.core.utils.file import pickle_hash +from smarts.core.utils.logging import timeit + from . import types from .generators import TrafficGenerator @@ -41,6 +43,76 @@ logger = logging.getLogger(__file__) +def _build_graph(scenario: types.Scenario, base_dir: str) -> Dict[str, Any]: + graph = collections.defaultdict(list) + + if scenario.map_spec: + graph["map_spec"] = [os.path.join(base_dir, "map_spec.pkl")] + + if scenario.traffic: + for name, traffic in scenario.traffic.items(): + ext = "smarts" if traffic.engine == "SMARTS" else "rou" + artifact_path = os.path.join(base_dir, "traffic", f"{name}.{ext}.xml") + graph["traffic"].append(artifact_path) + + if scenario.ego_missions: + graph["ego_missions"] = [os.path.join(base_dir, "missions.pkl")] + + if scenario.social_agent_missions: + for name in scenario.social_agent_missions.keys(): + artifact_path = os.path.join(base_dir, "social_agents", name) + graph["social_agent_missions"].append(artifact_path) + + if scenario.bubbles: + graph["bubbles"] = [os.path.join(base_dir, "bubbles.pkl")] + + if scenario.friction_maps: + graph["friction_maps"] = [os.path.join(base_dir, "friction_map.pkl")] + + if scenario.traffic_histories: + for dataset in scenario.traffic_histories: + artifact_path = os.path.join(base_dir, f"{dataset.name}.shf") + graph["traffic_histories"].append(artifact_path) + + return graph + + +def _needs_build( + db_conn: sqlite3.Connection, scenario_obj: Any, artifact_paths: List[str] +) -> bool: + if scenario_obj is None: + return False # There's no object in the DSL, so nothing to build + if not all([os.path.exists(f) for f in artifact_paths]): + return True # Some of the expected output files don't exist + + expected_hash = pickle_hash(scenario_obj) + + for f in artifact_paths: + cur = db_conn.cursor() + cur.execute( + """SELECT scenario_obj_hash FROM Artifacts WHERE artifact_path=?;""", (f,) + ) + row = cur.fetchone() + cur.close() + + if row is None: + return True # Artifact is not in the db + + artifact_hash = row[0] + if artifact_hash != expected_hash: + return True # Hash does not match, out of date + return False + + +def _update_artifact(db_conn: sqlite3.Connection, artifact_path: str, hash_val: str): + query = """REPLACE INTO Artifacts (artifact_path, scenario_obj_hash) + VALUES(?, ?);""" + cur = db_conn.cursor() + cur.execute(query, (artifact_path, hash_val)) + db_conn.commit() + cur.close() + + def gen_scenario( scenario: types.Scenario, output_dir: Union[str, Path], @@ -55,82 +127,140 @@ def gen_scenario( # us to simplify our serialization between SStudio and SMARTS. output_dir = str(output_dir) + build_graph = _build_graph(scenario, output_dir) + + # Create DB for build caching + db_path = os.path.join(output_dir, "build.db") + db_conn = sqlite3.connect(db_path) + + cur = db_conn.cursor() + cur.execute( + """CREATE TABLE IF NOT EXISTS Artifacts ( + artifact_path TEXT PRIMARY KEY, + scenario_obj_hash TEXT + ) WITHOUT ROWID""" + ) + db_conn.commit() + cur.close() + + with timeit("gen_map", logger.info): + if _needs_build(db_conn, scenario.map_spec, build_graph["map_spec"]): + gen_map(output_dir, scenario.map_spec) + _update_artifact( + db_conn, build_graph["map_spec"][0], pickle_hash(scenario.map_spec) + ) + map_spec = scenario.map_spec + else: + map_spec = types.MapSpec(source=output_dir) + + with timeit("gen_traffic", logger.info): + if _needs_build(db_conn, scenario.traffic, build_graph["traffic"]): + for name, traffic in scenario.traffic.items(): + gen_traffic( + scenario=output_dir, + traffic=traffic, + name=name, + seed=seed, + overwrite=overwrite, + map_spec=map_spec, + ) + hash = pickle_hash(scenario.traffic) + for artifact in build_graph["traffic"]: + _update_artifact(db_conn, artifact, hash) + + with timeit("ego_missions", logger.info): + if _needs_build(db_conn, scenario.ego_missions, build_graph["ego_missions"]): + missions = [] + for mission in scenario.ego_missions: + if isinstance(mission, types.GroupedLapMission): + gen_group_laps( + scenario=output_dir, + begin=mission.route.begin, + end=mission.route.end, + grid_offset=mission.offset, + used_lanes=mission.lanes, + vehicle_count=mission.actor_count, + num_laps=mission.num_laps, + seed=seed, + overwrite=overwrite, + map_spec=map_spec, + ) + else: + missions.append(mission) + + if missions: + gen_missions( + scenario=output_dir, + missions=missions, + seed=seed, + overwrite=overwrite, + map_spec=map_spec, + ) - if scenario.map_spec: - gen_map(output_dir, scenario.map_spec) - map_spec = scenario.map_spec - else: - map_spec = types.MapSpec(source=output_dir) - - if scenario.traffic: - for name, traffic in scenario.traffic.items(): - gen_traffic( - scenario=output_dir, - traffic=traffic, - name=name, - seed=seed, - overwrite=overwrite, - map_spec=map_spec, + _update_artifact( + db_conn, + build_graph["ego_missions"][0], + pickle_hash(scenario.ego_missions), ) - if scenario.ego_missions: - missions = [] - for mission in scenario.ego_missions: - if isinstance(mission, types.GroupedLapMission): - gen_group_laps( + with timeit("social_agent_missions", logger.info): + if _needs_build( + db_conn, + scenario.social_agent_missions, + build_graph["social_agent_missions"], + ): + for name, (actors, missions) in scenario.social_agent_missions.items(): + if not ( + isinstance(actors, collections.abc.Sequence) + and isinstance(missions, collections.abc.Sequence) + ): + raise ValueError("Actors and missions must be sequences") + + gen_social_agent_missions( + name=name, scenario=output_dir, - begin=mission.route.begin, - end=mission.route.end, - grid_offset=mission.offset, - used_lanes=mission.lanes, - vehicle_count=mission.actor_count, - num_laps=mission.num_laps, + social_agent_actor=actors, + missions=missions, seed=seed, - overwrite=overwrite, map_spec=map_spec, ) - else: - missions.append(mission) - if missions: - gen_missions( - scenario=output_dir, - missions=missions, - seed=seed, - overwrite=overwrite, - map_spec=map_spec, + hash = pickle_hash(scenario.social_agent_missions) + for artifact in build_graph["social_agent_missions"]: + _update_artifact(db_conn, artifact, hash) + + with timeit("bubbles", logger.info): + if _needs_build(db_conn, scenario.bubbles, build_graph["bubbles"]): + gen_bubbles(scenario=output_dir, bubbles=scenario.bubbles) + _update_artifact( + db_conn, build_graph["bubbles"][0], pickle_hash(scenario.bubbles) ) - if scenario.social_agent_missions: - for name, (actors, missions) in scenario.social_agent_missions.items(): - if not ( - isinstance(actors, collections.abc.Sequence) - and isinstance(missions, collections.abc.Sequence) - ): - raise ValueError("Actors and missions must be sequences") - - gen_social_agent_missions( - name=name, + with timeit("friction_maps", logger.info): + if _needs_build(db_conn, scenario.friction_maps, build_graph["friction_maps"]): + gen_friction_map( + scenario=output_dir, surface_patches=scenario.friction_maps + ) + _update_artifact( + db_conn, + build_graph["friction_maps"][0], + pickle_hash(scenario.friction_maps), + ) + + with timeit("traffic_histories", logger.info): + if _needs_build( + db_conn, scenario.traffic_histories, build_graph["traffic_histories"] + ): + gen_traffic_histories( scenario=output_dir, - social_agent_actor=actors, - missions=missions, - seed=seed, + histories_datasets=scenario.traffic_histories, + overwrite=overwrite, map_spec=map_spec, ) - if scenario.bubbles: - gen_bubbles(scenario=output_dir, bubbles=scenario.bubbles) - - if scenario.friction_maps: - gen_friction_map(scenario=output_dir, surface_patches=scenario.friction_maps) - - if scenario.traffic_histories: - gen_traffic_histories( - scenario=output_dir, - histories_datasets=scenario.traffic_histories, - overwrite=overwrite, - map_spec=map_spec, - ) + hash = pickle_hash(scenario.traffic_histories) + for artifact in build_graph["traffic_histories"]: + _update_artifact(db_conn, artifact, hash) def gen_map(scenario: str, map_spec: types.MapSpec, output_dir: Optional[str] = None): @@ -457,6 +587,10 @@ def gen_traffic_histories( road_map = None # shared across all history_datasets in scenario for hdsr in histories_datasets: assert isinstance(hdsr, types.TrafficHistoryDataset) + if not hdsr.input_path: + print(f"skipping placeholder dataset spec '{hdsr.name}'.") + continue + from smarts.sstudio import genhistories map_bbox = None diff --git a/smarts/sstudio/scenario_construction.py b/smarts/sstudio/scenario_construction.py index 5f166dd62b..29b71d88f2 100644 --- a/smarts/sstudio/scenario_construction.py +++ b/smarts/sstudio/scenario_construction.py @@ -94,6 +94,7 @@ def clean_scenario(scenario: str): "history_mission.pkl", "*.shf", "*-AUTOGEN.net.xml", + "build.db", ] p = Path(scenario) for file_name in to_be_removed: diff --git a/smarts/sstudio/types.py b/smarts/sstudio/types.py index bbc444fe5d..8c818148a9 100644 --- a/smarts/sstudio/types.py +++ b/smarts/sstudio/types.py @@ -18,16 +18,13 @@ # OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN # THE SOFTWARE. import collections.abc as collections_abc -import hashlib import logging import math -import pickle import random -from ctypes import c_int64 from dataclasses import dataclass, field from enum import IntEnum from sys import maxsize -from typing import Any, Callable, Dict, NewType, Optional, Sequence, Tuple, Union +from typing import Any, Callable, Dict, Optional, Sequence, Tuple, Union import numpy as np from shapely.affinity import rotate as shapely_rotate @@ -45,6 +42,7 @@ from smarts.core.coordinates import RefLinePoint from smarts.core.default_map_builder import get_road_map from smarts.core.road_map import RoadMap +from smarts.core.utils.file import pickle_hash_int from smarts.core.utils.id import SocialAgentId from smarts.core.utils.math import rotate_cw_around_point @@ -54,14 +52,6 @@ class _SUMO_PARAMS_MODE(IntEnum): KEEP_SNAKE_CASE = 1 -def _pickle_hash(obj) -> int: - pickle_bytes = pickle.dumps(obj, protocol=4) - hasher = hashlib.md5() - hasher.update(pickle_bytes) - val = int(hasher.hexdigest(), 16) - return c_int64(val).value - - class _SumoParams(collections_abc.Mapping): """For some Sumo params (e.g. LaneChangingModel) the arguments are in title case with a given prefix. Subclassing this class allows for an automatic way to map @@ -304,7 +294,7 @@ class TrafficActor(Actor): junction_model: JunctionModel = field(default_factory=JunctionModel, hash=False) def __hash__(self) -> int: - return _pickle_hash(self) + return pickle_hash_int(self) @property def id(self) -> str: @@ -426,7 +416,7 @@ def id(self) -> str: return "route-{}-{}-{}-".format( "_".join(map(str, self.begin)), "_".join(map(str, self.end)), - _pickle_hash(self), + pickle_hash_int(self), ) @property @@ -435,7 +425,7 @@ def roads(self): return (self.begin[0],) + self.via + (self.end[0],) def __hash__(self): - return _pickle_hash(self) + return pickle_hash_int(self) def __eq__(self, other): return self.__class__ == other.__class__ and hash(self) == hash(other) @@ -490,13 +480,13 @@ def id(self) -> str: """The unique id of this flow.""" return "flow-{}-{}-".format( self.route.id, - str(_pickle_hash(sorted(self.actors.items(), key=lambda a: a[0].name))), + str(pickle_hash_int(sorted(self.actors.items(), key=lambda a: a[0].name))), ) def __hash__(self): # Custom hash since self.actors is not hashable, here we first convert to a # frozenset. - return _pickle_hash((self.route, self.rate, frozenset(self.actors.items()))) + return pickle_hash_int((self.route, self.rate, frozenset(self.actors.items()))) def __eq__(self, other): return self.__class__ == other.__class__ and hash(self) == hash(other) From fea9f07a4b803918f1a1d43e7975b5989828c20b Mon Sep 17 00:00:00 2001 From: Saul Field Date: Fri, 18 Nov 2022 16:59:47 -0500 Subject: [PATCH 02/19] Refactor scenario caching, use SMARTS version in hash function --- smarts/core/utils/file.py | 10 +++- smarts/sstudio/genscenario.py | 93 +++++++++++++++++------------------ 2 files changed, 52 insertions(+), 51 deletions(-) diff --git a/smarts/core/utils/file.py b/smarts/core/utils/file.py index 72d5f554dd..1eef093c13 100644 --- a/smarts/core/utils/file.py +++ b/smarts/core/utils/file.py @@ -17,7 +17,6 @@ # LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, # OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN # THE SOFTWARE. -from ctypes import c_int64 import dataclasses import hashlib import os @@ -25,8 +24,11 @@ import shutil import struct from contextlib import contextmanager +from ctypes import c_int64 from typing import Generator +import smarts + def file_in_folder(filename: str, path: str) -> bool: """Checks to see if a file exists @@ -111,11 +113,15 @@ def file_md5_hash(file_path: str) -> str: return str(hasher.hexdigest()) -def pickle_hash(obj) -> str: +def pickle_hash(obj, include_version=False) -> str: """Converts a Python object to a hash value. NOTE: NOT stable across different Python versions.""" pickle_bytes = pickle.dumps(obj, protocol=4) hasher = hashlib.md5() hasher.update(pickle_bytes) + + if include_version: + hasher.update(smarts.VERSION.encode()) + return hasher.hexdigest() diff --git a/smarts/sstudio/genscenario.py b/smarts/sstudio/genscenario.py index 9aaf7d4633..bf17ec8c22 100644 --- a/smarts/sstudio/genscenario.py +++ b/smarts/sstudio/genscenario.py @@ -41,6 +41,7 @@ logging.basicConfig(level=logging.WARNING) logger = logging.getLogger(__file__) +logger.setLevel(logging.INFO) def _build_graph(scenario: types.Scenario, base_dir: str) -> Dict[str, Any]: @@ -78,20 +79,20 @@ def _build_graph(scenario: types.Scenario, base_dir: str) -> Dict[str, Any]: def _needs_build( - db_conn: sqlite3.Connection, scenario_obj: Any, artifact_paths: List[str] + db_conn: sqlite3.Connection, + scenario_obj: Any, + artifact_paths: List[str], + obj_hash: str, ) -> bool: if scenario_obj is None: return False # There's no object in the DSL, so nothing to build if not all([os.path.exists(f) for f in artifact_paths]): return True # Some of the expected output files don't exist - expected_hash = pickle_hash(scenario_obj) - - for f in artifact_paths: + query = """SELECT scenario_obj_hash FROM Artifacts WHERE artifact_path=?;""" + for artifact_path in artifact_paths: cur = db_conn.cursor() - cur.execute( - """SELECT scenario_obj_hash FROM Artifacts WHERE artifact_path=?;""", (f,) - ) + cur.execute(query, (artifact_path,)) row = cur.fetchone() cur.close() @@ -99,16 +100,19 @@ def _needs_build( return True # Artifact is not in the db artifact_hash = row[0] - if artifact_hash != expected_hash: + if artifact_hash != obj_hash: return True # Hash does not match, out of date return False -def _update_artifact(db_conn: sqlite3.Connection, artifact_path: str, hash_val: str): +def _update_artifacts( + db_conn: sqlite3.Connection, artifact_paths: List[str], hash_val: str +): query = """REPLACE INTO Artifacts (artifact_path, scenario_obj_hash) VALUES(?, ?);""" cur = db_conn.cursor() - cur.execute(query, (artifact_path, hash_val)) + for artifact_path in artifact_paths: + cur.execute(query, (artifact_path, hash_val)) db_conn.commit() cur.close() @@ -126,7 +130,7 @@ def gen_scenario( # XXX: For now this simply coalesces the sub-calls but in the future this allows # us to simplify our serialization between SStudio and SMARTS. - output_dir = str(output_dir) + output_dir = os.path.abspath(str(output_dir)) build_graph = _build_graph(scenario, output_dir) # Create DB for build caching @@ -144,17 +148,19 @@ def gen_scenario( cur.close() with timeit("gen_map", logger.info): - if _needs_build(db_conn, scenario.map_spec, build_graph["map_spec"]): + artifact_paths = build_graph["map_spec"] + obj_hash = pickle_hash(scenario.map_spec, True) + if _needs_build(db_conn, scenario.map_spec, artifact_paths, obj_hash): gen_map(output_dir, scenario.map_spec) - _update_artifact( - db_conn, build_graph["map_spec"][0], pickle_hash(scenario.map_spec) - ) + _update_artifacts(db_conn, artifact_paths, obj_hash) map_spec = scenario.map_spec else: map_spec = types.MapSpec(source=output_dir) - with timeit("gen_traffic", logger.info): - if _needs_build(db_conn, scenario.traffic, build_graph["traffic"]): + with timeit("traffic", logger.info): + artifact_paths = build_graph["traffic"] + obj_hash = pickle_hash(scenario.traffic, True) + if _needs_build(db_conn, scenario.traffic, artifact_paths, obj_hash): for name, traffic in scenario.traffic.items(): gen_traffic( scenario=output_dir, @@ -164,12 +170,12 @@ def gen_scenario( overwrite=overwrite, map_spec=map_spec, ) - hash = pickle_hash(scenario.traffic) - for artifact in build_graph["traffic"]: - _update_artifact(db_conn, artifact, hash) + _update_artifacts(db_conn, artifact_paths, obj_hash) with timeit("ego_missions", logger.info): - if _needs_build(db_conn, scenario.ego_missions, build_graph["ego_missions"]): + artifact_paths = build_graph["ego_missions"] + obj_hash = pickle_hash(scenario.ego_missions, True) + if _needs_build(db_conn, scenario.ego_missions, artifact_paths, obj_hash): missions = [] for mission in scenario.ego_missions: if isinstance(mission, types.GroupedLapMission): @@ -197,17 +203,13 @@ def gen_scenario( map_spec=map_spec, ) - _update_artifact( - db_conn, - build_graph["ego_missions"][0], - pickle_hash(scenario.ego_missions), - ) + _update_artifacts(db_conn, artifact_paths, obj_hash) with timeit("social_agent_missions", logger.info): + artifact_paths = build_graph["social_agent_missions"] + obj_hash = pickle_hash(scenario.social_agent_missions, True) if _needs_build( - db_conn, - scenario.social_agent_missions, - build_graph["social_agent_missions"], + db_conn, scenario.social_agent_missions, artifact_paths, obj_hash ): for name, (actors, missions) in scenario.social_agent_missions.items(): if not ( @@ -225,42 +227,35 @@ def gen_scenario( map_spec=map_spec, ) - hash = pickle_hash(scenario.social_agent_missions) - for artifact in build_graph["social_agent_missions"]: - _update_artifact(db_conn, artifact, hash) + _update_artifacts(db_conn, artifact_paths, obj_hash) with timeit("bubbles", logger.info): - if _needs_build(db_conn, scenario.bubbles, build_graph["bubbles"]): + artifact_paths = build_graph["bubbles"] + obj_hash = pickle_hash(scenario.bubbles, True) + if _needs_build(db_conn, scenario.bubbles, artifact_paths, obj_hash): gen_bubbles(scenario=output_dir, bubbles=scenario.bubbles) - _update_artifact( - db_conn, build_graph["bubbles"][0], pickle_hash(scenario.bubbles) - ) + _update_artifacts(db_conn, artifact_paths, obj_hash) with timeit("friction_maps", logger.info): - if _needs_build(db_conn, scenario.friction_maps, build_graph["friction_maps"]): + artifact_paths = build_graph["friction_maps"] + obj_hash = pickle_hash(scenario.friction_maps, True) + if _needs_build(db_conn, scenario.friction_maps, artifact_paths, obj_hash): gen_friction_map( scenario=output_dir, surface_patches=scenario.friction_maps ) - _update_artifact( - db_conn, - build_graph["friction_maps"][0], - pickle_hash(scenario.friction_maps), - ) + _update_artifacts(db_conn, artifact_paths, obj_hash) with timeit("traffic_histories", logger.info): - if _needs_build( - db_conn, scenario.traffic_histories, build_graph["traffic_histories"] - ): + artifact_paths = build_graph["traffic_histories"] + obj_hash = pickle_hash(scenario.traffic_histories, True) + if _needs_build(db_conn, scenario.traffic_histories, artifact_paths, obj_hash): gen_traffic_histories( scenario=output_dir, histories_datasets=scenario.traffic_histories, overwrite=overwrite, map_spec=map_spec, ) - - hash = pickle_hash(scenario.traffic_histories) - for artifact in build_graph["traffic_histories"]: - _update_artifact(db_conn, artifact, hash) + _update_artifacts(db_conn, artifact_paths, obj_hash) def gen_map(scenario: str, map_spec: types.MapSpec, output_dir: Optional[str] = None): From d24574152820f2a56d42594a9f9bbed03a505665 Mon Sep 17 00:00:00 2001 From: Saul Field Date: Mon, 21 Nov 2022 17:11:40 -0500 Subject: [PATCH 03/19] Add a build/ directory for all scenario artifacts --- scenarios/sumo/loop/map.net.xml | 2 +- .../sumo/loop/{traffic => }/rerouter.add.xml | 2 +- smarts/core/scenario.py | 18 ++++----- smarts/core/sumo_traffic_simulation.py | 2 +- smarts/core/tests/test_done_criteria.py | 2 +- .../tests/test_motion_planner_provider.py | 2 +- smarts/core/tests/test_observations.py | 2 +- smarts/core/tests/test_renderers.py | 2 +- smarts/core/tests/test_smarts.py | 2 +- smarts/core/tests/test_smarts_reset.py | 2 +- smarts/core/tests/test_traffic_simulation.py | 2 +- smarts/sstudio/genscenario.py | 37 ++++++++++++------- smarts/sstudio/scenario_construction.py | 6 +++ smarts/sstudio/tests/baseline.rou.xml | 6 +-- .../scenarios/analysis/sumo_experiment.py | 4 +- ultra/ultra/scenarios/generate_scenarios.py | 6 +-- 16 files changed, 56 insertions(+), 41 deletions(-) rename scenarios/sumo/loop/{traffic => }/rerouter.add.xml (97%) diff --git a/scenarios/sumo/loop/map.net.xml b/scenarios/sumo/loop/map.net.xml index e29c5eb94c..bb78b9b670 100644 --- a/scenarios/sumo/loop/map.net.xml +++ b/scenarios/sumo/loop/map.net.xml @@ -30,7 +30,7 @@ - + diff --git a/scenarios/sumo/loop/traffic/rerouter.add.xml b/scenarios/sumo/loop/rerouter.add.xml similarity index 97% rename from scenarios/sumo/loop/traffic/rerouter.add.xml rename to scenarios/sumo/loop/rerouter.add.xml index 77fa4ee866..b78aa50cc3 100644 --- a/scenarios/sumo/loop/traffic/rerouter.add.xml +++ b/scenarios/sumo/loop/rerouter.add.xml @@ -30,7 +30,7 @@ - + diff --git a/smarts/core/scenario.py b/smarts/core/scenario.py index e5636132b9..c3d142cf54 100644 --- a/smarts/core/scenario.py +++ b/smarts/core/scenario.py @@ -106,7 +106,7 @@ def __init__( "Scenario route property has been deprecated in favor of traffic_specs. Please update your code.", category=DeprecationWarning, ) - traffic_path = os.path.join(scenario_root, "traffic") + traffic_path = os.path.join(scenario_root, "build", "traffic") self._traffic_specs = [os.path.join(traffic_path, route)] self._missions = missions or {} self._bubbles = Scenario._discover_bubbles(scenario_root) @@ -276,7 +276,7 @@ def variations_for_all_scenario_roots( @staticmethod def discover_agent_missions_count(scenario_root): """Retrieve the agent missions from the given scenario directory.""" - missions_file = os.path.join(scenario_root, "missions.pkl") + missions_file = os.path.join(scenario_root, "build", "missions.pkl") if os.path.exists(missions_file): with open(missions_file, "rb") as f: return len(pickle.load(f)) @@ -297,7 +297,7 @@ def discover_agent_missions(scenario_root, agents_to_be_briefed): road_map, _ = Scenario.build_map(scenario_root) missions = [] - missions_file = os.path.join(scenario_root, "missions.pkl") + missions_file = os.path.join(scenario_root, "build", "missions.pkl") if os.path.exists(missions_file): with open(missions_file, "rb") as f: missions = pickle.load(f) @@ -331,7 +331,7 @@ def discover_friction_map(scenario_root) -> List[Dict[str, Any]]: parameters of the specified surface patch. """ surface_patches = [] - friction_map_file = os.path.join(scenario_root, "friction_map.pkl") + friction_map_file = os.path.join(scenario_root, "build", "friction_map.pkl") if os.path.exists(friction_map_file): with open(friction_map_file, "rb") as f: map_surface_patches = pickle.load(f) @@ -362,7 +362,7 @@ def _discover_social_agents_info( ) road_map, _ = Scenario.build_map(scenario_root) - social_agents_path = os.path.join(scenario_root, "social_agents") + social_agents_path = os.path.join(scenario_root, "build", "social_agents") if not os.path.exists(social_agents_path): return [] @@ -479,7 +479,7 @@ def discover_map( Returns: A new map spec. """ - path = os.path.join(scenario_root, "map_spec.pkl") + path = os.path.join(scenario_root, "build", "map_spec.pkl") if not os.path.exists(path): # Use our default map builder if none specified by scenario... return MapSpec( @@ -508,14 +508,14 @@ def discover_routes(scenario_root): return sorted( [ os.path.basename(r) - for r in glob.glob(os.path.join(scenario_root, "traffic", "*.rou.xml")) + for r in glob.glob(os.path.join(scenario_root, "build", "traffic", "*.rou.xml")) ] ) @staticmethod def discover_traffic(scenario_root: str) -> List[Optional[List[str]]]: """Discover the traffic spec files in the given scenario.""" - traffic_path = os.path.join(scenario_root, "traffic") + traffic_path = os.path.join(scenario_root, "build", "traffic") # combine any SMARTS and SUMO traffic together... sumo_traffic = glob.glob(os.path.join(traffic_path, "*.rou.xml")) smarts_traffic = glob.glob(os.path.join(traffic_path, "*.smarts.xml")) @@ -527,7 +527,7 @@ def discover_traffic(scenario_root: str) -> List[Optional[List[str]]]: @staticmethod def _discover_bubbles(scenario_root): - path = os.path.join(scenario_root, "bubbles.pkl") + path = os.path.join(scenario_root, "build", "bubbles.pkl") if not os.path.exists(path): return [] diff --git a/smarts/core/sumo_traffic_simulation.py b/smarts/core/sumo_traffic_simulation.py index f293737bcd..acf44f502c 100644 --- a/smarts/core/sumo_traffic_simulation.py +++ b/smarts/core/sumo_traffic_simulation.py @@ -284,7 +284,7 @@ def _base_sumo_load_params(self): ] rerouter_file = ( - Path(self._scenario.road_map.source).parent / "traffic" / "rerouter.add.xml" + Path(self._scenario.road_map.source).parent / "rerouter.add.xml" ) if rerouter_file.exists(): load_params.append(f"--additional-files={rerouter_file}") diff --git a/smarts/core/tests/test_done_criteria.py b/smarts/core/tests/test_done_criteria.py index 9d24395203..150a94f031 100644 --- a/smarts/core/tests/test_done_criteria.py +++ b/smarts/core/tests/test_done_criteria.py @@ -41,7 +41,7 @@ def scenario(): scenario = Scenario( scenario_root="scenarios/sumo/loop", - traffic_specs=["scenarios/sumo/loop/traffic/basic.rou.xml"], + traffic_specs=["scenarios/sumo/loop/build/traffic/basic.rou.xml"], ) return scenario diff --git a/smarts/core/tests/test_motion_planner_provider.py b/smarts/core/tests/test_motion_planner_provider.py index 41253d17c2..be65d7ffe3 100644 --- a/smarts/core/tests/test_motion_planner_provider.py +++ b/smarts/core/tests/test_motion_planner_provider.py @@ -55,7 +55,7 @@ def loop_scenario(): ) scenario = Scenario( scenario_root="scenarios/sumo/loop", - traffic_specs=["scenarios/sumo/loop/traffic/basic.rou.xml"], + traffic_specs=["scenarios/sumo/loop/build/traffic/basic.rou.xml"], missions={AGENT_ID: mission}, ) return scenario diff --git a/smarts/core/tests/test_observations.py b/smarts/core/tests/test_observations.py index bdfabf693c..6549b83c92 100644 --- a/smarts/core/tests/test_observations.py +++ b/smarts/core/tests/test_observations.py @@ -257,7 +257,7 @@ def scenario(): ) return Scenario( scenario_root="scenarios/sumo/intersections/2lane", - traffic_specs=["scenarios/sumo/intersections/2lane/traffic/vertical.rou.xml"], + traffic_specs=["scenarios/sumo/intersections/2lane/build/traffic/vertical.rou.xml"], missions={AGENT_ID: mission}, ) diff --git a/smarts/core/tests/test_renderers.py b/smarts/core/tests/test_renderers.py index e3c583b2f7..4943e58046 100644 --- a/smarts/core/tests/test_renderers.py +++ b/smarts/core/tests/test_renderers.py @@ -89,7 +89,7 @@ def scenario(): ) scenario = Scenario( scenario_root="scenarios/sumo/loop", - traffic_specs=["scenarios/sumo/loop/traffic/basic.rou.xml"], + traffic_specs=["scenarios/sumo/loop/build/traffic/basic.rou.xml"], missions={AGENT_ID: mission}, ) return scenario diff --git a/smarts/core/tests/test_smarts.py b/smarts/core/tests/test_smarts.py index b029717e3a..5fb0d792ef 100644 --- a/smarts/core/tests/test_smarts.py +++ b/smarts/core/tests/test_smarts.py @@ -46,7 +46,7 @@ def scenarios(): ) scenario = Scenario( scenario_root="scenarios/sumo/loop", - traffic_specs=["scenarios/sumo/loop/traffic/basic.rou.xml"], + traffic_specs=["scenarios/sumo/loop/build/traffic/basic.rou.xml"], missions={"Agent-007": mission}, ) return cycle([scenario]) diff --git a/smarts/core/tests/test_smarts_reset.py b/smarts/core/tests/test_smarts_reset.py index 27054d26f9..594c0f51e1 100644 --- a/smarts/core/tests/test_smarts_reset.py +++ b/smarts/core/tests/test_smarts_reset.py @@ -42,7 +42,7 @@ def scenarios(): ) scenario = Scenario( scenario_root="scenarios/sumo/loop", - traffic_specs=["scenarios/sumo/loop/traffic/basic.rou.xml"], + traffic_specs=["scenarios/sumo/loop/build/traffic/basic.rou.xml"], missions={"Agent-007": mission}, ) return cycle([scenario]) diff --git a/smarts/core/tests/test_traffic_simulation.py b/smarts/core/tests/test_traffic_simulation.py index 66abe6cbb5..026ad28d73 100644 --- a/smarts/core/tests/test_traffic_simulation.py +++ b/smarts/core/tests/test_traffic_simulation.py @@ -46,7 +46,7 @@ def scenarios(): ) scenario = Scenario( scenario_root="scenarios/sumo/loop", - traffic_specs=["scenarios/sumo/loop/traffic/basic.rou.xml"], + traffic_specs=["scenarios/sumo/loop/build/traffic/basic.rou.xml"], missions={"Agent-007": mission}, ) return cycle([scenario]) diff --git a/smarts/sstudio/genscenario.py b/smarts/sstudio/genscenario.py index bf17ec8c22..2c0b5d2f06 100644 --- a/smarts/sstudio/genscenario.py +++ b/smarts/sstudio/genscenario.py @@ -41,7 +41,7 @@ logging.basicConfig(level=logging.WARNING) logger = logging.getLogger(__file__) -logger.setLevel(logging.INFO) +logger.setLevel(logging.WARNING) def _build_graph(scenario: types.Scenario, base_dir: str) -> Dict[str, Any]: @@ -130,11 +130,13 @@ def gen_scenario( # XXX: For now this simply coalesces the sub-calls but in the future this allows # us to simplify our serialization between SStudio and SMARTS. - output_dir = os.path.abspath(str(output_dir)) - build_graph = _build_graph(scenario, output_dir) + scenario_dir = os.path.abspath(str(output_dir)) + build_dir = os.path.join(scenario_dir, "build") + build_graph = _build_graph(scenario, build_dir) + os.makedirs(build_dir, exist_ok=True) # Create DB for build caching - db_path = os.path.join(output_dir, "build.db") + db_path = os.path.join(build_dir, "build.db") db_conn = sqlite3.connect(db_path) cur = db_conn.cursor() @@ -151,11 +153,11 @@ def gen_scenario( artifact_paths = build_graph["map_spec"] obj_hash = pickle_hash(scenario.map_spec, True) if _needs_build(db_conn, scenario.map_spec, artifact_paths, obj_hash): - gen_map(output_dir, scenario.map_spec) + gen_map(scenario_dir, scenario.map_spec) _update_artifacts(db_conn, artifact_paths, obj_hash) map_spec = scenario.map_spec else: - map_spec = types.MapSpec(source=output_dir) + map_spec = types.MapSpec(source=scenario_dir) with timeit("traffic", logger.info): artifact_paths = build_graph["traffic"] @@ -163,7 +165,7 @@ def gen_scenario( if _needs_build(db_conn, scenario.traffic, artifact_paths, obj_hash): for name, traffic in scenario.traffic.items(): gen_traffic( - scenario=output_dir, + scenario=scenario_dir, traffic=traffic, name=name, seed=seed, @@ -260,7 +262,11 @@ def gen_scenario( def gen_map(scenario: str, map_spec: types.MapSpec, output_dir: Optional[str] = None): """Saves a map spec to file.""" - output_path = os.path.join(output_dir or scenario, "map_spec.pkl") + build_dir = os.path.join(scenario, "build") + output_dir = os.path.join(output_dir or build_dir, "map") + os.makedirs(output_dir, exist_ok=True) + + output_path = os.path.join(output_dir, "map_spec.pkl") with open(output_path, "wb") as f: # we use cloudpickle here instead of pickle because the # map_spec object may contain a reference to a map_builder callable @@ -280,7 +286,8 @@ def gen_traffic( not provided, the scenario directory is used.""" assert name != "missions", "The name 'missions' is reserved for missions!" - output_dir = os.path.join(output_dir or scenario, "traffic") + build_dir = os.path.join(scenario, "build") + output_dir = os.path.join(output_dir or build_dir, "traffic") os.makedirs(output_dir, exist_ok=True) generator = TrafficGenerator(scenario, map_spec, overwrite=overwrite) @@ -335,7 +342,7 @@ def gen_social_agent_missions( if len(actor_names) != len(set(actor_names)): raise ValueError(f"Actor names={actor_names} must not contain duplicates") - output_dir = os.path.join(scenario, "social_agents") + output_dir = os.path.join(scenario, "build", "social_agents") saved = _gen_missions( scenario=scenario, missions=missions, @@ -374,12 +381,13 @@ def gen_missions( An optional map specification that takes precedence over scenario directory information. """ + output_dir = os.path.join(scenario, "build") saved = _gen_missions( scenario=scenario, missions=missions, actors=[types.TrafficActor(name="car")], name="missions", - output_dir=scenario, + output_dir=output_dir, seed=seed, overwrite=overwrite, map_spec=map_spec, @@ -462,7 +470,7 @@ def gen_bubbles(scenario: str, bubbles: Sequence[types.Bubble]): bubbles: The bubbles to add to the scenario. """ - output_path = os.path.join(scenario, "bubbles.pkl") + output_path = os.path.join(scenario, "build", "bubbles.pkl") with open(output_path, "wb") as f: pickle.dump(bubbles, f) @@ -471,7 +479,7 @@ def gen_friction_map(scenario: str, surface_patches: Sequence[types.RoadSurfaceP """Generates friction map file according to the surface patches defined in scenario file. """ - output_path = os.path.join(scenario, "friction_map.pkl") + output_path = os.path.join(scenario, "build", "friction_map.pkl") with open(output_path, "wb") as f: pickle.dump(surface_patches, f) @@ -599,4 +607,5 @@ def gen_traffic_histories( logger.warn( f"no map_spec supplied, so unable to filter off-map coordinates and/or flip_y for {hdsr.name}" ) - genhistories.import_dataset(hdsr, scenario, overwrite, map_bbox) + output_dir = os.path.join(scenario, "build") + genhistories.import_dataset(hdsr, output_dir, overwrite, map_bbox) diff --git a/smarts/sstudio/scenario_construction.py b/smarts/sstudio/scenario_construction.py index 29b71d88f2..a0afcac0b1 100644 --- a/smarts/sstudio/scenario_construction.py +++ b/smarts/sstudio/scenario_construction.py @@ -18,6 +18,7 @@ # OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN # THE SOFTWARE. import os +import shutil import subprocess import sys import tempfile @@ -97,6 +98,11 @@ def clean_scenario(scenario: str): "build.db", ] p = Path(scenario) + + shutil.rmtree(p / "build", ignore_errors=True) + shutil.rmtree(p / "traffic", ignore_errors=True) + shutil.rmtree(p / "social_agents", ignore_errors=True) + for file_name in to_be_removed: for f in p.glob(file_name): # Remove file diff --git a/smarts/sstudio/tests/baseline.rou.xml b/smarts/sstudio/tests/baseline.rou.xml index bc519b4346..fe8f176f69 100644 --- a/smarts/sstudio/tests/baseline.rou.xml +++ b/smarts/sstudio/tests/baseline.rou.xml @@ -9,8 +9,8 @@ - - + + @@ -19,7 +19,7 @@ - + diff --git a/ultra/ultra/scenarios/analysis/sumo_experiment.py b/ultra/ultra/scenarios/analysis/sumo_experiment.py index 1724aca58b..27c599ebc9 100644 --- a/ultra/ultra/scenarios/analysis/sumo_experiment.py +++ b/ultra/ultra/scenarios/analysis/sumo_experiment.py @@ -575,7 +575,7 @@ def dynamic_vehicle_gen_probability_func(pattern, current_step): "-n", current_scenario_dir + "/map.net.xml", "-r", - current_scenario_dir + "/traffic/all.rou.xml", + current_scenario_dir + "/build/traffic/all.rou.xml", "--seed", str(np.random.randint(0, run_per_scenario)), ] @@ -615,7 +615,7 @@ def dynamic_vehicle_gen_probability_func(pattern, current_step): # Default sumo instruction for 4 lane_t -# sumo -n research/edmonton/intersections/scenarios/task1/hard_4lane_t_80kmh_heavy_traffic_stress_test_t_intersection-mission-0-flow-0/map.net.xml -r research/edmonton/intersections/scenarios/task1/hard_4lane_t_80kmh_heavy_traffic_stress_test_t_intersection-mission-0-flow-0/traffic/all.rou.xml --remote-port=8813 +# sumo -n research/edmonton/intersections/scenarios/task1/hard_4lane_t_80kmh_heavy_traffic_stress_test_t_intersection-mission-0-flow-0/map.net.xml -r research/edmonton/intersections/scenarios/task1/hard_4lane_t_80kmh_heavy_traffic_stress_test_t_intersection-mission-0-flow-0/build/traffic/all.rou.xml --remote-port=8813 # Run command example # python research/edmonton/intersections/scenarios/sumo_experiment.py --level="hard" --task="1" --scenario_dir="research/edmonton/intersections/scenarios/task1/hard_4lane_t_80kmh_heavy_traffic_stress_test_t_intersection-mission-0" --figure_dir="research/edmonton/intersections/scenarios/task1/figures" --setting_id="hard_t_intersection_4_vehicle_prob_0_05" --num_scenario=100 if __name__ == "__main__": diff --git a/ultra/ultra/scenarios/generate_scenarios.py b/ultra/ultra/scenarios/generate_scenarios.py index 347ba7b065..72442ccf6f 100644 --- a/ultra/ultra/scenarios/generate_scenarios.py +++ b/ultra/ultra/scenarios/generate_scenarios.py @@ -202,7 +202,7 @@ def add_stops_to_traffic( A list of vehicle IDs that is appended to. Each stopped vehicle's ID is appended to this list as stopped vehicles should not be hijacked. """ - route_file_path = f"{scenario}/traffic/all.rou.xml" + route_file_path = f"{scenario}/build/traffic/all.rou.xml" map_file = sumolib.net.readNet(f"{scenario}/map.net.xml") vehicle_types = list(sumolib.output.parse(route_file_path, "vType")) vehicles = list() @@ -355,7 +355,7 @@ def generate_left_turn_missions( scenario = save_dir + f"-flow-{seed}" # Remove old traffic route if it exists(otherwise, won't update to new flows) - if os.path.exists(f"{scenario}/traffic/all.rou.xml"): + if os.path.exists(f"{scenario}/build/traffic/all.rou.xml"): shutil.rmtree(scenario) for route_key, route_info in route_distributions["routes"].items(): @@ -431,7 +431,7 @@ def generate_left_turn_missions( # Patch: Remove route files from traffic folder to make intersection empty. if traffic_density == "no-traffic": - os.remove(f"{scenario}/traffic/all.rou.xml") + os.remove(f"{scenario}/build/traffic/all.rou.xml") if stopwatcher_behavior or "ego_hijacking_params" not in route_distributions: mission_objects = [Mission(ego_route) for ego_route in ego_routes] From 9c7d97368a7cc6037493f622f8d2bf8775e1f903 Mon Sep 17 00:00:00 2001 From: Saul Field Date: Mon, 21 Nov 2022 21:04:31 -0500 Subject: [PATCH 04/19] Type fix --- smarts/sstudio/genscenario.py | 1 + 1 file changed, 1 insertion(+) diff --git a/smarts/sstudio/genscenario.py b/smarts/sstudio/genscenario.py index 2c0b5d2f06..ba4bc24b93 100644 --- a/smarts/sstudio/genscenario.py +++ b/smarts/sstudio/genscenario.py @@ -72,6 +72,7 @@ def _build_graph(scenario: types.Scenario, base_dir: str) -> Dict[str, Any]: if scenario.traffic_histories: for dataset in scenario.traffic_histories: + assert isinstance(dataset, types.TrafficHistoryDataset) artifact_path = os.path.join(base_dir, f"{dataset.name}.shf") graph["traffic_histories"].append(artifact_path) From eed10f06b66f650938c2834faf5b18acc793b62e Mon Sep 17 00:00:00 2001 From: Saul Field Date: Tue, 22 Nov 2022 11:51:48 -0500 Subject: [PATCH 05/19] Type fix --- ultra/ultra/scenarios/generate_scenarios.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/ultra/ultra/scenarios/generate_scenarios.py b/ultra/ultra/scenarios/generate_scenarios.py index 72442ccf6f..2d95536aef 100644 --- a/ultra/ultra/scenarios/generate_scenarios.py +++ b/ultra/ultra/scenarios/generate_scenarios.py @@ -176,7 +176,7 @@ def bubble_config_to_bubble_object( ), margin=BUBBLE_MARGIN, limit=None, - exclusion_prefixes=vehicles_to_not_hijack, + exclusion_prefixes=tuple(vehicles_to_not_hijack), follow_actor_id=None, follow_offset=None, keep_alive=False, @@ -461,7 +461,9 @@ def generate_left_turn_missions( length=zone_range[1], n_lanes=(ego_route.begin[1] + 1), ), # Area to hijack. - exclusion_prefixes=vehicles_to_not_hijack, # Don't hijack these. + exclusion_prefixes=tuple( + vehicles_to_not_hijack + ), # Don't hijack these. ), ) for ego_route in ego_routes From 222f6962e4b41d312eea97674cb378156981a84d Mon Sep 17 00:00:00 2001 From: Saul Field Date: Tue, 22 Nov 2022 15:29:20 -0500 Subject: [PATCH 06/19] Cache glb file, track map file hash, refactoring --- cli/studio.py | 13 +-- examples/env/figure_eight_env.py | 2 +- smarts/core/default_map_builder.py | 5 +- smarts/core/scenario.py | 6 +- smarts/core/sumo_traffic_simulation.py | 4 +- smarts/sstudio/genscenario.py | 134 +++++++++++++++++------- smarts/sstudio/scenario_construction.py | 23 +--- 7 files changed, 110 insertions(+), 77 deletions(-) diff --git a/cli/studio.py b/cli/studio.py index 8e15cfd6ab..45adfa59f0 100644 --- a/cli/studio.py +++ b/cli/studio.py @@ -42,12 +42,6 @@ def scenario_cli(): default=False, help="Clean previously generated artifacts first", ) -@click.option( - "--allow-offset-map", - is_flag=True, - default=False, - help="Allows road network to be offset from the origin. If not specified, creates a new network file if necessary.", -) @click.option( "--seed", type=int, @@ -62,12 +56,11 @@ def build_scenario(clean: bool, allow_offset_map: bool, scenario: str, seed: int assert seed == None or isinstance(seed, (int)) - build_single_scenario(clean, allow_offset_map, scenario, seed, click.echo) + build_single_scenario(clean, scenario, seed, click.echo) def _build_single_scenario_proc( clean: bool, - allow_offset_map: bool, scenario: str, semaphore: synchronize.Semaphore, seed: int, @@ -76,7 +69,7 @@ def _build_single_scenario_proc( semaphore.acquire() try: - build_single_scenario(clean, allow_offset_map, scenario, seed, click.echo) + build_single_scenario(clean, scenario, seed, click.echo) finally: semaphore.release() @@ -144,7 +137,7 @@ def _build_all_scenarios( scenario = f"{scenarios_path}/{p.relative_to(scenarios_path)}" proc = Process( target=_build_single_scenario_proc, - args=(clean, allow_offset_maps, scenario, sema, seed), + args=(clean, scenario, sema, seed), ) all_processes.append((scenario, proc)) proc.start() diff --git a/examples/env/figure_eight_env.py b/examples/env/figure_eight_env.py index 4d4c05cf19..f76d31cc3c 100644 --- a/examples/env/figure_eight_env.py +++ b/examples/env/figure_eight_env.py @@ -25,7 +25,7 @@ def entry_point(*args, **kwargs): ## Note: can build the scenario here from smarts.sstudio.scenario_construction import build_single_scenario - build_single_scenario(clean=True, allow_offset_map=True, scenario=scenario) + build_single_scenario(clean=True, scenario=scenario) hiwayenv = HiWayEnv( agent_specs={"agent-007": agent_spec}, scenarios=[scenario], diff --git a/smarts/core/default_map_builder.py b/smarts/core/default_map_builder.py index 76c3f4dea0..20f785ff9e 100644 --- a/smarts/core/default_map_builder.py +++ b/smarts/core/default_map_builder.py @@ -57,7 +57,8 @@ def _clear_cache(): _WAYMO_MAP = 3 -def _find_mapfile_in_dir(map_dir: str) -> Tuple[int, str]: +def find_mapfile_in_dir(map_dir: str) -> Tuple[int, str]: + """Looks in a given directory for a supported map file.""" map_filename_type = { "map.net.xml": _SUMO_MAP, "shifted_map-AUTOGEN.net.xml": _SUMO_MAP, @@ -100,7 +101,7 @@ def get_road_map(map_spec) -> Tuple[Optional[RoadMap], Optional[str]]: assert map_spec.source, "A road map source must be specified" if os.path.isdir(map_spec.source): - map_type, map_source = _find_mapfile_in_dir(map_spec.source) + map_type, map_source = find_mapfile_in_dir(map_spec.source) else: map_type = _UNKNOWN_MAP map_source = map_spec.source diff --git a/smarts/core/scenario.py b/smarts/core/scenario.py index c3d142cf54..82d3e3159c 100644 --- a/smarts/core/scenario.py +++ b/smarts/core/scenario.py @@ -508,7 +508,9 @@ def discover_routes(scenario_root): return sorted( [ os.path.basename(r) - for r in glob.glob(os.path.join(scenario_root, "build", "traffic", "*.rou.xml")) + for r in glob.glob( + os.path.join(scenario_root, "build", "traffic", "*.rou.xml") + ) ] ) @@ -937,7 +939,7 @@ def route_filepath(self): @property def map_glb_filepath(self): """The map geometry filepath.""" - return os.path.join(self._root, "map.glb") + return os.path.join(self._root, "map", "map.glb") def unique_sumo_log_file(self): """A unique logging file for SUMO logging.""" diff --git a/smarts/core/sumo_traffic_simulation.py b/smarts/core/sumo_traffic_simulation.py index acf44f502c..8bf96a7ba2 100644 --- a/smarts/core/sumo_traffic_simulation.py +++ b/smarts/core/sumo_traffic_simulation.py @@ -283,9 +283,7 @@ def _base_sumo_load_params(self): "--end=31536000", # keep the simulation running for a year ] - rerouter_file = ( - Path(self._scenario.road_map.source).parent / "rerouter.add.xml" - ) + rerouter_file = Path(self._scenario.road_map.source).parent / "rerouter.add.xml" if rerouter_file.exists(): load_params.append(f"--additional-files={rerouter_file}") if self._auto_start: diff --git a/smarts/sstudio/genscenario.py b/smarts/sstudio/genscenario.py index ba4bc24b93..72e5460662 100644 --- a/smarts/sstudio/genscenario.py +++ b/smarts/sstudio/genscenario.py @@ -32,8 +32,9 @@ from typing import Any, Dict, List, Optional, Sequence, Tuple, Union import cloudpickle +from smarts.core.default_map_builder import find_mapfile_in_dir -from smarts.core.utils.file import pickle_hash +from smarts.core.utils.file import file_md5_hash, path2hash, pickle_hash from smarts.core.utils.logging import timeit from . import types @@ -47,8 +48,10 @@ def _build_graph(scenario: types.Scenario, base_dir: str) -> Dict[str, Any]: graph = collections.defaultdict(list) + graph["map"] = [os.path.join(base_dir, "map", "map.glb")] + if scenario.map_spec: - graph["map_spec"] = [os.path.join(base_dir, "map_spec.pkl")] + graph["map_spec"] = [os.path.join(base_dir, "map", "map_spec.pkl")] if scenario.traffic: for name, traffic in scenario.traffic.items(): @@ -61,7 +64,7 @@ def _build_graph(scenario: types.Scenario, base_dir: str) -> Dict[str, Any]: if scenario.social_agent_missions: for name in scenario.social_agent_missions.keys(): - artifact_path = os.path.join(base_dir, "social_agents", name) + artifact_path = os.path.join(base_dir, "social_agents", f"{name}.pkl") graph["social_agent_missions"].append(artifact_path) if scenario.bubbles: @@ -84,9 +87,12 @@ def _needs_build( scenario_obj: Any, artifact_paths: List[str], obj_hash: str, + map_needs_build: Optional[bool] = None, ) -> bool: if scenario_obj is None: return False # There's no object in the DSL, so nothing to build + if map_needs_build: + return True # Passed as an override for artifacts that depend on the map if not all([os.path.exists(f) for f in artifact_paths]): return True # Some of the expected output files don't exist @@ -150,20 +156,61 @@ def gen_scenario( db_conn.commit() cur.close() - with timeit("gen_map", logger.info): - artifact_paths = build_graph["map_spec"] - obj_hash = pickle_hash(scenario.map_spec, True) - if _needs_build(db_conn, scenario.map_spec, artifact_paths, obj_hash): + # Map spec + artifact_paths = build_graph["map_spec"] + obj_hash = pickle_hash(scenario.map_spec, True) + if _needs_build(db_conn, scenario.map_spec, artifact_paths, obj_hash): + with timeit("map_spec", logger.info): gen_map(scenario_dir, scenario.map_spec) _update_artifacts(db_conn, artifact_paths, obj_hash) - map_spec = scenario.map_spec - else: - map_spec = types.MapSpec(source=scenario_dir) - - with timeit("traffic", logger.info): - artifact_paths = build_graph["traffic"] - obj_hash = pickle_hash(scenario.traffic, True) - if _needs_build(db_conn, scenario.traffic, artifact_paths, obj_hash): + map_spec = scenario.map_spec + else: + map_spec = types.MapSpec(source=scenario_dir) + + if map_spec.shift_to_origin and scenario.traffic_histories: + logger.warning( + "Attempting to shift map with traffic histories." + "The data may no longer line up with the map." + ) + + # Track changes to map file itself, if we can find it + if os.path.isdir(map_spec.source): + _, map_source = find_mapfile_in_dir(map_spec.source) + else: + map_source = map_spec.source + if os.path.isfile(map_source): + map_hash = file_md5_hash(map_source) + else: + map_hash = path2hash(map_source) + + # Map glb file + artifact_paths = build_graph["map"] + map_needs_rebuild = _needs_build(db_conn, map_spec, artifact_paths, map_hash) + if map_needs_rebuild: + with timeit("map_glb", logger.info): + road_map, _ = map_spec.builder_fn(map_spec) + if not road_map: + logger.warning( + "No reference to a RoadNetwork file was found in {}, or one could not be created. " + "Please make sure the path passed is a valid Scenario with RoadNetwork file required " + "(or a way to create one) for scenario building.".format( + scenario_dir + ) + ) + return + + map_dir = os.path.join(build_dir, "map") + os.makedirs(map_dir, exist_ok=True) + road_map.to_glb(os.path.join(map_dir, "map.glb")) + _update_artifacts(db_conn, artifact_paths, map_hash) + + # Traffic + artifact_paths = build_graph["traffic"] + obj_hash = pickle_hash(scenario.traffic, True) + if _needs_build( + db_conn, scenario.traffic, artifact_paths, obj_hash, map_needs_rebuild + ): + with timeit("traffic", logger.info): for name, traffic in scenario.traffic.items(): gen_traffic( scenario=scenario_dir, @@ -175,10 +222,13 @@ def gen_scenario( ) _update_artifacts(db_conn, artifact_paths, obj_hash) - with timeit("ego_missions", logger.info): - artifact_paths = build_graph["ego_missions"] - obj_hash = pickle_hash(scenario.ego_missions, True) - if _needs_build(db_conn, scenario.ego_missions, artifact_paths, obj_hash): + # Ego missions + artifact_paths = build_graph["ego_missions"] + obj_hash = pickle_hash(scenario.ego_missions, True) + if _needs_build( + db_conn, scenario.ego_missions, artifact_paths, obj_hash, map_needs_rebuild + ): + with timeit("ego_missions", logger.info): missions = [] for mission in scenario.ego_missions: if isinstance(mission, types.GroupedLapMission): @@ -208,12 +258,17 @@ def gen_scenario( _update_artifacts(db_conn, artifact_paths, obj_hash) - with timeit("social_agent_missions", logger.info): - artifact_paths = build_graph["social_agent_missions"] - obj_hash = pickle_hash(scenario.social_agent_missions, True) - if _needs_build( - db_conn, scenario.social_agent_missions, artifact_paths, obj_hash - ): + # Social agent missions + artifact_paths = build_graph["social_agent_missions"] + obj_hash = pickle_hash(scenario.social_agent_missions, True) + if _needs_build( + db_conn, + scenario.social_agent_missions, + artifact_paths, + obj_hash, + map_needs_rebuild, + ): + with timeit("social_agent_missions", logger.info): for name, (actors, missions) in scenario.social_agent_missions.items(): if not ( isinstance(actors, collections.abc.Sequence) @@ -232,26 +287,31 @@ def gen_scenario( _update_artifacts(db_conn, artifact_paths, obj_hash) - with timeit("bubbles", logger.info): - artifact_paths = build_graph["bubbles"] - obj_hash = pickle_hash(scenario.bubbles, True) - if _needs_build(db_conn, scenario.bubbles, artifact_paths, obj_hash): + # Bubbles + artifact_paths = build_graph["bubbles"] + obj_hash = pickle_hash(scenario.bubbles, True) + if _needs_build(db_conn, scenario.bubbles, artifact_paths, obj_hash): + with timeit("bubbles", logger.info): gen_bubbles(scenario=output_dir, bubbles=scenario.bubbles) _update_artifacts(db_conn, artifact_paths, obj_hash) - with timeit("friction_maps", logger.info): - artifact_paths = build_graph["friction_maps"] - obj_hash = pickle_hash(scenario.friction_maps, True) - if _needs_build(db_conn, scenario.friction_maps, artifact_paths, obj_hash): + # Friction maps + artifact_paths = build_graph["friction_maps"] + obj_hash = pickle_hash(scenario.friction_maps, True) + if _needs_build(db_conn, scenario.friction_maps, artifact_paths, obj_hash): + with timeit("friction_maps", logger.info): gen_friction_map( scenario=output_dir, surface_patches=scenario.friction_maps ) _update_artifacts(db_conn, artifact_paths, obj_hash) - with timeit("traffic_histories", logger.info): - artifact_paths = build_graph["traffic_histories"] - obj_hash = pickle_hash(scenario.traffic_histories, True) - if _needs_build(db_conn, scenario.traffic_histories, artifact_paths, obj_hash): + # Traffic histories + artifact_paths = build_graph["traffic_histories"] + obj_hash = pickle_hash(scenario.traffic_histories, True) + if _needs_build( + db_conn, scenario.traffic_histories, artifact_paths, obj_hash, map_needs_rebuild + ): + with timeit("traffic_histories", logger.info): gen_traffic_histories( scenario=output_dir, histories_datasets=scenario.traffic_histories, diff --git a/smarts/sstudio/scenario_construction.py b/smarts/sstudio/scenario_construction.py index a0afcac0b1..d00a62b172 100644 --- a/smarts/sstudio/scenario_construction.py +++ b/smarts/sstudio/scenario_construction.py @@ -17,7 +17,6 @@ # LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, # OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN # THE SOFTWARE. -import os import shutil import subprocess import sys @@ -28,7 +27,6 @@ def build_single_scenario( clean: bool, - allow_offset_map: bool, scenario: str, seed: Optional[int] = None, log: Optional[Callable[[Any], None]] = None, @@ -39,7 +37,6 @@ def build_single_scenario( clean_scenario(scenario) scenario_root = Path(scenario) - scenario_root_str = str(scenario_root) scenario_py = scenario_root / "scenario.py" if scenario_py.exists(): @@ -57,24 +54,6 @@ def build_single_scenario( else: subprocess.check_call([sys.executable, "scenario.py"], cwd=scenario_root) - from smarts.core.scenario import Scenario - - traffic_histories = Scenario.discover_traffic_histories(scenario_root_str) - # don't shift maps for scenarios with traffic histories since history data must line up with map - shift_to_origin = not allow_offset_map and not bool(traffic_histories) - - map_spec = Scenario.discover_map(scenario_root_str, shift_to_origin=shift_to_origin) - road_map, _ = map_spec.builder_fn(map_spec) - if not road_map: - log( - "No reference to a RoadNetwork file was found in {}, or one could not be created. " - "Please make sure the path passed is a valid Scenario with RoadNetwork file required " - "(or a way to create one) for scenario building.".format(scenario_root_str) - ) - return - - road_map.to_glb(os.path.join(scenario_root, "map.glb")) - def clean_scenario(scenario: str): """Remove all cached scenario files in the given scenario directory.""" @@ -102,7 +81,7 @@ def clean_scenario(scenario: str): shutil.rmtree(p / "build", ignore_errors=True) shutil.rmtree(p / "traffic", ignore_errors=True) shutil.rmtree(p / "social_agents", ignore_errors=True) - + for file_name in to_be_removed: for f in p.glob(file_name): # Remove file From 56e5df3d18eaeaff829cd061115ebc8428925034 Mon Sep 17 00:00:00 2001 From: Saul Field Date: Tue, 22 Nov 2022 15:34:59 -0500 Subject: [PATCH 07/19] Test fixes --- cli/studio.py | 2 +- smarts/core/scenario.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/cli/studio.py b/cli/studio.py index 45adfa59f0..a83c60b609 100644 --- a/cli/studio.py +++ b/cli/studio.py @@ -49,7 +49,7 @@ def scenario_cli(): help="Set the base seed of the scenario.", ) @click.argument("scenario", type=click.Path(exists=True), metavar="") -def build_scenario(clean: bool, allow_offset_map: bool, scenario: str, seed: int): +def build_scenario(clean: bool, scenario: str, seed: int): click.echo(f"build-scenario {scenario}") from smarts.sstudio.scenario_construction import build_single_scenario diff --git a/smarts/core/scenario.py b/smarts/core/scenario.py index 82d3e3159c..77ac917c33 100644 --- a/smarts/core/scenario.py +++ b/smarts/core/scenario.py @@ -939,7 +939,7 @@ def route_filepath(self): @property def map_glb_filepath(self): """The map geometry filepath.""" - return os.path.join(self._root, "map", "map.glb") + return os.path.join(self._root, "build", "map", "map.glb") def unique_sumo_log_file(self): """A unique logging file for SUMO logging.""" From cbd1a738c56ce8c2753399ed52abf6b6a0efc44a Mon Sep 17 00:00:00 2001 From: Saul Field Date: Tue, 22 Nov 2022 18:02:15 -0500 Subject: [PATCH 08/19] Test fixes --- scenarios/sumo/figure_eight/scenario.py | 9 ++++++++ .../sumo/intersections/2lane/scenario.py | 23 ++++++++++++++----- .../sumo/intersections/4lane/scenario.py | 6 ++++- 3 files changed, 31 insertions(+), 7 deletions(-) create mode 100644 scenarios/sumo/figure_eight/scenario.py diff --git a/scenarios/sumo/figure_eight/scenario.py b/scenarios/sumo/figure_eight/scenario.py new file mode 100644 index 0000000000..abd41dcaeb --- /dev/null +++ b/scenarios/sumo/figure_eight/scenario.py @@ -0,0 +1,9 @@ +from pathlib import Path + +from smarts.sstudio.genscenario import gen_scenario +from smarts.sstudio.types import Scenario + +gen_scenario( + scenario=Scenario(), + output_dir=Path(__file__).parent, +) diff --git a/scenarios/sumo/intersections/2lane/scenario.py b/scenarios/sumo/intersections/2lane/scenario.py index d63f68be20..f2938ce7ea 100644 --- a/scenarios/sumo/intersections/2lane/scenario.py +++ b/scenarios/sumo/intersections/2lane/scenario.py @@ -1,18 +1,18 @@ -import os +from pathlib import Path -from smarts.sstudio import gen_traffic +from smarts.sstudio.genscenario import gen_scenario from smarts.sstudio.types import ( Distribution, Flow, JunctionModel, LaneChangingModel, + MapSpec, Route, + Scenario, Traffic, TrafficActor, ) -scenario = os.path.dirname(os.path.realpath(__file__)) - impatient_car = TrafficActor( name="car", speed=Distribution(sigma=0.2, mean=1.0), @@ -53,6 +53,8 @@ ("east-EW", "north-SN"), ] +traffic = {} + for name, routes in { "vertical": vertical_routes, "horizontal": horizontal_routes, @@ -60,7 +62,7 @@ "turns": turn_left_routes + turn_right_routes, "all": vertical_routes + horizontal_routes + turn_left_routes + turn_right_routes, }.items(): - traffic = Traffic( + traffic[name] = Traffic( flows=[ Flow( route=Route( @@ -75,4 +77,13 @@ ] ) - gen_traffic(scenario, traffic, name=name) +gen_scenario( + scenario=Scenario( + traffic=traffic, + map_spec=MapSpec( + source=Path(__file__).parent, + shift_to_origin=True, + ), + ), + output_dir=Path(__file__).parent, +) diff --git a/scenarios/sumo/intersections/4lane/scenario.py b/scenarios/sumo/intersections/4lane/scenario.py index 0aeb7f10ff..8c309a6f46 100644 --- a/scenarios/sumo/intersections/4lane/scenario.py +++ b/scenarios/sumo/intersections/4lane/scenario.py @@ -1,4 +1,3 @@ -import os from pathlib import Path from smarts.sstudio.genscenario import gen_scenario @@ -6,6 +5,7 @@ EndlessMission, Flow, JunctionEdgeIDResolver, + MapSpec, Mission, RandomRoute, Route, @@ -88,6 +88,10 @@ ) }, ego_missions=ego_missions, + map_spec=MapSpec( + source=Path(__file__).parent, + shift_to_origin=True, + ), ) gen_scenario( From 0565333a4c0ac7bd87b04bcb52b2ec308c5c060a Mon Sep 17 00:00:00 2001 From: Saul Field Date: Tue, 29 Nov 2022 14:49:30 -0500 Subject: [PATCH 09/19] Update changelog, make gen_ functions private, and update scenarios --- CHANGELOG.md | 1 + docs/minimal_scenario_studio.py | 17 ++++----- .../intersections/2lane_circle/scenario.py | 6 ++-- .../sumo/tests/same_location/scenario.py | 7 ++-- scenarios/sumo/zoo_intersection/scenario.py | 14 +++++--- smarts/core/tests/test_scenario.py | 6 ++-- smarts/core/utils/geometry.py | 3 ++ smarts/sstudio/__init__.py | 8 ----- smarts/sstudio/genscenario.py | 36 +++++++++---------- smarts/sstudio/tests/test_generate.py | 6 ++-- ultra/ultra/scenarios/generate_scenarios.py | 8 ++--- zoo/evaluation/scenarios/cross/scenario.py | 4 +-- zoo/evaluation/scenarios/cross_1/scenario.py | 6 ++-- zoo/evaluation/scenarios/cross_2/scenario.py | 4 +-- zoo/evaluation/scenarios/merge/scenario.py | 4 +-- zoo/evaluation/scenarios/merge_1/scenario.py | 4 +-- zoo/evaluation/scenarios/merge_2/scenario.py | 4 +-- .../straight_change-lane_1/scenario.py | 4 +-- .../straight_change-lane_2/scenario.py | 4 +-- .../scenarios/straight_pick_lane/scenario.py | 4 +-- .../scenarios/straight_straight_1/scenario.py | 4 +-- .../scenarios/straight_straight_2/scenario.py | 4 +-- .../straight_turn-left_1/scenario.py | 4 +-- .../straight_turn-left_2/scenario.py | 4 +-- .../turn-left_turn-left_1/scenario.py | 4 +-- .../turn-left_turn-left_2/scenario.py | 4 +-- .../turn-right_turn-left_1/scenario.py | 4 +-- .../turn-right_turn-left_2/scenario.py | 4 +-- .../scenarios/turnleft_pick_lane/scenario.py | 4 +-- 29 files changed, 91 insertions(+), 95 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 80d93a261d..7bdb977c21 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -45,6 +45,7 @@ Copy and pasting the git commit messages is __NOT__ enough. - Renamed `examples/history_vehicles_replacement_for_imitation_learning.py` to `examples/traffic_histories_vehicle_replacement.py`. - `SumoTrafficSimulation` will now try to hand-off the vehicles it controls to the new SMARTS background traffic provider by default if the Sumo provider crashes. - SMARTS now gives an error about a suspected lack of junction edges in sumo maps on loading of them. +- Substantial changes to scenario builds to make scenario iteration faster. Scenario build artifacts are now cached and built incrementally, meaning that subsequent builds (without the `clean` option) will only build the artifacts that depend on the changed DSL objects. All build artifacts are now in a local `build/` directory in each scenario's directory. NOTE: the `allow_offset_map` option has been removed. This must now be set in a `MapSpec` object in the scenario.py if this option is needed. Another requirement is that all scenarios must have a `scenario.py`, and must call `gen_scenario()`, rather than the individual `gen_` functions, which are now private. ### Removed - Removed support for deprecated json-based and YAML formats for traffic histories. diff --git a/docs/minimal_scenario_studio.py b/docs/minimal_scenario_studio.py index 25213dfacf..ab5b26825d 100644 --- a/docs/minimal_scenario_studio.py +++ b/docs/minimal_scenario_studio.py @@ -1,9 +1,7 @@ from pathlib import Path from smarts.sstudio import types as t -from smarts.sstudio import gen_traffic, gen_bubbles, gen_missions - -scenario = str(Path(__file__).parent) +from smarts.sstudio import gen_scenario # Definition of a traffic flow traffic = t.Traffic( @@ -22,12 +20,11 @@ ] ) -# The call to generate traffic -gen_traffic(scenario, traffic, name="basic") +missions = [ + t.Mission(t.Route(begin=("west", 0, 0), end=("east", 0, "max"))), +] -gen_missions( - scenario, - [ - t.Mission(t.Route(begin=("west", 0, 0), end=("east", 0, "max"))), - ], +gen_scenario( + t.Scenario(traffic={"basic": traffic}, ego_missions=missions), + output_dir=Path(__file__).parent, ) diff --git a/scenarios/sumo/intersections/2lane_circle/scenario.py b/scenarios/sumo/intersections/2lane_circle/scenario.py index b4630bb866..243fd2aa66 100644 --- a/scenarios/sumo/intersections/2lane_circle/scenario.py +++ b/scenarios/sumo/intersections/2lane_circle/scenario.py @@ -1,6 +1,6 @@ import os -from smarts.sstudio import gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_social_agent_missions from smarts.sstudio.types import Mission, Route, SocialAgentActor scenario = os.path.dirname(os.path.realpath(__file__)) @@ -36,14 +36,14 @@ # }, # ) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=laner_agent, name=f"s-agent-{laner_agent.name}", missions=[Mission(Route(begin=("edge-east-EW", 0, 5), end=("edge-west-EW", 0, 5)))], ) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=buddha_agent, name=f"s-agent-{buddha_agent.name}", diff --git a/scenarios/sumo/tests/same_location/scenario.py b/scenarios/sumo/tests/same_location/scenario.py index 5017d79f01..ece7dc6a50 100644 --- a/scenarios/sumo/tests/same_location/scenario.py +++ b/scenarios/sumo/tests/same_location/scenario.py @@ -1,8 +1,7 @@ from pathlib import Path -from typing import Any, Tuple import smarts.sstudio.types as types -from smarts.sstudio import gen_missions, gen_traffic +from smarts.sstudio.genscenario import _gen_agent_missions, _gen_traffic scenario = str(Path(__file__).parent) @@ -26,10 +25,10 @@ ] ) -gen_missions( +_gen_agent_missions( scenario, missions=[ types.Mission(shared_route), ], ) -gen_traffic(scenario, traffic, "traffic") +_gen_traffic(scenario, traffic, "traffic") diff --git a/scenarios/sumo/zoo_intersection/scenario.py b/scenarios/sumo/zoo_intersection/scenario.py index 4a713008f6..5387930a3a 100644 --- a/scenarios/sumo/zoo_intersection/scenario.py +++ b/scenarios/sumo/zoo_intersection/scenario.py @@ -1,7 +1,11 @@ import os import random -from smarts.sstudio import gen_missions, gen_social_agent_missions, gen_traffic +from smarts.sstudio.genscenario import ( + _gen_agent_missions, + _gen_social_agent_missions, + _gen_traffic, +) from smarts.sstudio.types import ( Distribution, EndlessMission, @@ -58,7 +62,7 @@ ) for seed in [0, 5]: - gen_traffic( + _gen_traffic( scenario, traffic, name=f"{name}-{seed}", @@ -83,14 +87,14 @@ initial_speed=20, ) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent2, name=f"s-agent-{social_agent2.name}", missions=[Mission(RandomRoute())], ) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent1, name=f"s-agent-{social_agent1.name}", @@ -101,7 +105,7 @@ ) # Agent Missions -gen_missions( +_gen_agent_missions( scenario=scenario, missions=[ Mission(Route(begin=("edge-east-EW", 0, 10), end=("edge-south-NS", 0, 10))), diff --git a/smarts/core/tests/test_scenario.py b/smarts/core/tests/test_scenario.py index 7e7c5b21f6..99788b8287 100644 --- a/smarts/core/tests/test_scenario.py +++ b/smarts/core/tests/test_scenario.py @@ -26,7 +26,7 @@ from smarts.core.scenario import Scenario from smarts.core.utils.id import SocialAgentId -from smarts.sstudio import gen_missions, gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_agent_missions, _gen_social_agent_missions from smarts.sstudio.types import Mission, Route, SocialAgentActor AGENT_ID = "Agent-007" @@ -57,14 +57,14 @@ def scenario_root(): begin=("edge-north-NS", 1, 0), end=("edge-south-NS", 1, "max") ) missions = [Mission(route=route)] * 2 # double up - gen_social_agent_missions( + _gen_social_agent_missions( scenario_root, social_agent_actor=actors, name=name, missions=missions, ) - gen_missions( + _gen_agent_missions( scenario_root, missions=[ Mission( diff --git a/smarts/core/utils/geometry.py b/smarts/core/utils/geometry.py index 881512ec52..b254b1a1d1 100644 --- a/smarts/core/utils/geometry.py +++ b/smarts/core/utils/geometry.py @@ -86,6 +86,9 @@ def generate_meshes_from_polygons( if -1 not in face: faces.append(face) + if not vertices or not faces: + continue + mesh = trimesh.Trimesh(vertices=vertices, faces=faces, metadata=metadata) # Trimesh doesn't support a coordinate-system="z-up" configuration, so we diff --git a/smarts/sstudio/__init__.py b/smarts/sstudio/__init__.py index 3c166f618f..54ed21bcb9 100644 --- a/smarts/sstudio/__init__.py +++ b/smarts/sstudio/__init__.py @@ -23,15 +23,7 @@ from typing import List from .genscenario import ( - gen_bubbles, - gen_friction_map, - gen_group_laps, - gen_map, - gen_missions, gen_scenario, - gen_social_agent_missions, - gen_traffic, - gen_traffic_histories, ) # PYTHONHASHSEED must be "random", unset (default `None`), or an integer in range [0; 4294967295] diff --git a/smarts/sstudio/genscenario.py b/smarts/sstudio/genscenario.py index 72e5460662..17a230fac8 100644 --- a/smarts/sstudio/genscenario.py +++ b/smarts/sstudio/genscenario.py @@ -161,7 +161,7 @@ def gen_scenario( obj_hash = pickle_hash(scenario.map_spec, True) if _needs_build(db_conn, scenario.map_spec, artifact_paths, obj_hash): with timeit("map_spec", logger.info): - gen_map(scenario_dir, scenario.map_spec) + _gen_map(scenario_dir, scenario.map_spec) _update_artifacts(db_conn, artifact_paths, obj_hash) map_spec = scenario.map_spec else: @@ -212,7 +212,7 @@ def gen_scenario( ): with timeit("traffic", logger.info): for name, traffic in scenario.traffic.items(): - gen_traffic( + _gen_traffic( scenario=scenario_dir, traffic=traffic, name=name, @@ -232,7 +232,7 @@ def gen_scenario( missions = [] for mission in scenario.ego_missions: if isinstance(mission, types.GroupedLapMission): - gen_group_laps( + _gen_group_laps( scenario=output_dir, begin=mission.route.begin, end=mission.route.end, @@ -248,7 +248,7 @@ def gen_scenario( missions.append(mission) if missions: - gen_missions( + _gen_agent_missions( scenario=output_dir, missions=missions, seed=seed, @@ -276,7 +276,7 @@ def gen_scenario( ): raise ValueError("Actors and missions must be sequences") - gen_social_agent_missions( + _gen_social_agent_missions( name=name, scenario=output_dir, social_agent_actor=actors, @@ -292,7 +292,7 @@ def gen_scenario( obj_hash = pickle_hash(scenario.bubbles, True) if _needs_build(db_conn, scenario.bubbles, artifact_paths, obj_hash): with timeit("bubbles", logger.info): - gen_bubbles(scenario=output_dir, bubbles=scenario.bubbles) + _gen_bubbles(scenario=output_dir, bubbles=scenario.bubbles) _update_artifacts(db_conn, artifact_paths, obj_hash) # Friction maps @@ -300,7 +300,7 @@ def gen_scenario( obj_hash = pickle_hash(scenario.friction_maps, True) if _needs_build(db_conn, scenario.friction_maps, artifact_paths, obj_hash): with timeit("friction_maps", logger.info): - gen_friction_map( + _gen_friction_map( scenario=output_dir, surface_patches=scenario.friction_maps ) _update_artifacts(db_conn, artifact_paths, obj_hash) @@ -312,7 +312,7 @@ def gen_scenario( db_conn, scenario.traffic_histories, artifact_paths, obj_hash, map_needs_rebuild ): with timeit("traffic_histories", logger.info): - gen_traffic_histories( + _gen_traffic_histories( scenario=output_dir, histories_datasets=scenario.traffic_histories, overwrite=overwrite, @@ -321,7 +321,7 @@ def gen_scenario( _update_artifacts(db_conn, artifact_paths, obj_hash) -def gen_map(scenario: str, map_spec: types.MapSpec, output_dir: Optional[str] = None): +def _gen_map(scenario: str, map_spec: types.MapSpec, output_dir: Optional[str] = None): """Saves a map spec to file.""" build_dir = os.path.join(scenario, "build") output_dir = os.path.join(output_dir or build_dir, "map") @@ -334,7 +334,7 @@ def gen_map(scenario: str, map_spec: types.MapSpec, output_dir: Optional[str] = cloudpickle.dump(map_spec, f) -def gen_traffic( +def _gen_traffic( scenario: str, traffic: types.Traffic, name: str, @@ -358,7 +358,7 @@ def gen_traffic( logger.debug(f"Generated traffic for scenario={scenario}") -def gen_social_agent_missions( +def _gen_social_agent_missions( scenario: str, missions: Sequence[types.Mission], social_agent_actor: Union[types.SocialAgentActor, Sequence[types.SocialAgentActor]], @@ -395,7 +395,7 @@ def gen_social_agent_missions( # This doesn't support BoidAgentActor. Here we make that explicit if any(isinstance(actor, types.BoidAgentActor) for actor in actors): raise ValueError( - "gen_social_agent_missions(...) can't be called with BoidAgentActor, got:" + "_gen_social_agent_missions(...) can't be called with BoidAgentActor, got:" f"{actors}" ) @@ -419,7 +419,7 @@ def gen_social_agent_missions( logger.debug(f"Generated social agent missions for scenario={scenario}") -def gen_missions( +def _gen_agent_missions( scenario: str, missions: Sequence, seed: int = 42, @@ -458,7 +458,7 @@ def gen_missions( logger.debug(f"Generated missions for scenario={scenario}") -def gen_group_laps( +def _gen_group_laps( scenario: str, begin: Tuple[str, int, Any], end: Tuple[str, int, Any], @@ -511,7 +511,7 @@ def gen_group_laps( ) ) - saved = gen_missions( + saved = _gen_agent_missions( scenario=scenario, missions=missions, seed=seed, @@ -523,7 +523,7 @@ def gen_group_laps( logger.debug(f"Generated grouped lap missions for scenario={scenario}") -def gen_bubbles(scenario: str, bubbles: Sequence[types.Bubble]): +def _gen_bubbles(scenario: str, bubbles: Sequence[types.Bubble]): """Generates 'bubbles' in the scenario that capture vehicles for actors. Args: scenario: @@ -536,7 +536,7 @@ def gen_bubbles(scenario: str, bubbles: Sequence[types.Bubble]): pickle.dump(bubbles, f) -def gen_friction_map(scenario: str, surface_patches: Sequence[types.RoadSurfacePatch]): +def _gen_friction_map(scenario: str, surface_patches: Sequence[types.RoadSurfacePatch]): """Generates friction map file according to the surface patches defined in scenario file. """ @@ -631,7 +631,7 @@ def _validate_entry_tactic(mission): ), f"Zone edge `{z_edge}` is not the same edge as `types.Mission` route begin edge `{edge}`" -def gen_traffic_histories( +def _gen_traffic_histories( scenario: str, histories_datasets: Sequence[Union[types.TrafficHistoryDataset, str]], overwrite: bool, diff --git a/smarts/sstudio/tests/test_generate.py b/smarts/sstudio/tests/test_generate.py index 7d4bbe2523..5264ee2549 100644 --- a/smarts/sstudio/tests/test_generate.py +++ b/smarts/sstudio/tests/test_generate.py @@ -27,7 +27,7 @@ import pytest from smarts.core.scenario import Scenario -from smarts.sstudio import gen_map, gen_traffic +from smarts.sstudio.genscenario import _gen_map, _gen_traffic from smarts.sstudio.types import ( Distribution, Flow, @@ -81,7 +81,7 @@ def missions() -> Sequence[Mission]: def test_generate_traffic(traffic: Traffic): with tempfile.TemporaryDirectory() as temp_dir: - gen_traffic( + _gen_traffic( "scenarios/sumo/intersections/4lane_t", traffic, output_dir=temp_dir, @@ -110,7 +110,7 @@ def _compare_files(file1, file2): def _gen_map_from_spec(scenario_root: str, map_spec: MapSpec): with tempfile.TemporaryDirectory() as temp_dir: - gen_map(scenario_root, map_spec, output_dir=temp_dir) + _gen_map(scenario_root, map_spec, output_dir=temp_dir) found_map_spec = Scenario.discover_map(temp_dir) assert found_map_spec road_map = found_map_spec.builder_fn(found_map_spec) diff --git a/ultra/ultra/scenarios/generate_scenarios.py b/ultra/ultra/scenarios/generate_scenarios.py index 2d95536aef..9e62bcd1cd 100644 --- a/ultra/ultra/scenarios/generate_scenarios.py +++ b/ultra/ultra/scenarios/generate_scenarios.py @@ -40,7 +40,7 @@ import yaml from smarts.core.utils.sumo import sumolib -from smarts.sstudio import gen_bubbles, gen_missions, gen_traffic +from smarts.sstudio.genscenario import _gen_bubbles, _gen_missions, _gen_traffic from smarts.sstudio.types import ( Bubble, Distribution, @@ -423,7 +423,7 @@ def generate_left_turn_missions( vehicles_to_not_hijack = [] traffic = Traffic(flows=all_flows) try: - gen_traffic(scenario, traffic, name=f"all", seed=sumo_seed) + _gen_traffic(scenario, traffic, name=f"all", seed=sumo_seed) if stops: add_stops_to_traffic(scenario, stops, vehicles_to_not_hijack) except Exception as exception: @@ -471,7 +471,7 @@ def generate_left_turn_missions( # Shuffle the missions so agents don't do the same route all the time. if shuffle_missions: random.shuffle(mission_objects) - gen_missions(scenario, mission_objects) + _gen_missions(scenario, mission_objects) if bubbles: bubble_objects = [ @@ -480,7 +480,7 @@ def generate_left_turn_missions( ) for bubble_config in bubbles ] - gen_bubbles(scenario, bubble_objects) + _gen_bubbles(scenario, bubble_objects) if stopwatcher_behavior: metadata["stopwatcher"] = { diff --git a/zoo/evaluation/scenarios/cross/scenario.py b/zoo/evaluation/scenarios/cross/scenario.py index c412d9367f..4ca23955dc 100644 --- a/zoo/evaluation/scenarios/cross/scenario.py +++ b/zoo/evaluation/scenarios/cross/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio import gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/cross_1/scenario.py b/zoo/evaluation/scenarios/cross_1/scenario.py index 80e0fdb5d6..40f24df421 100644 --- a/zoo/evaluation/scenarios/cross_1/scenario.py +++ b/zoo/evaluation/scenarios/cross_1/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio import gen_missions, gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_agent_missions, _gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", @@ -18,7 +18,7 @@ ], ) -gen_missions( +_gen_agent_missions( scenario, [ t.Mission(t.Route(begin=("E3l-3", 1, 200), end=("E3-35", 1, 50))), diff --git a/zoo/evaluation/scenarios/cross_2/scenario.py b/zoo/evaluation/scenarios/cross_2/scenario.py index c412d9367f..4ca23955dc 100644 --- a/zoo/evaluation/scenarios/cross_2/scenario.py +++ b/zoo/evaluation/scenarios/cross_2/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio import gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/merge/scenario.py b/zoo/evaluation/scenarios/merge/scenario.py index 8429a1f533..2432e61c1d 100644 --- a/zoo/evaluation/scenarios/merge/scenario.py +++ b/zoo/evaluation/scenarios/merge/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio import gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/merge_1/scenario.py b/zoo/evaluation/scenarios/merge_1/scenario.py index 568c8eddaa..ab55eb6fbd 100644 --- a/zoo/evaluation/scenarios/merge_1/scenario.py +++ b/zoo/evaluation/scenarios/merge_1/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio import gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -10,7 +10,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/merge_2/scenario.py b/zoo/evaluation/scenarios/merge_2/scenario.py index 568c8eddaa..ab55eb6fbd 100644 --- a/zoo/evaluation/scenarios/merge_2/scenario.py +++ b/zoo/evaluation/scenarios/merge_2/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio import gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -10,7 +10,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/straight_change-lane_1/scenario.py b/zoo/evaluation/scenarios/straight_change-lane_1/scenario.py index a376920e91..f376c8b194 100755 --- a/zoo/evaluation/scenarios/straight_change-lane_1/scenario.py +++ b/zoo/evaluation/scenarios/straight_change-lane_1/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio import gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/straight_change-lane_2/scenario.py b/zoo/evaluation/scenarios/straight_change-lane_2/scenario.py index 1952b223df..a8a8a28876 100755 --- a/zoo/evaluation/scenarios/straight_change-lane_2/scenario.py +++ b/zoo/evaluation/scenarios/straight_change-lane_2/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio import gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/straight_pick_lane/scenario.py b/zoo/evaluation/scenarios/straight_pick_lane/scenario.py index 787c75fd16..ea3579af94 100644 --- a/zoo/evaluation/scenarios/straight_pick_lane/scenario.py +++ b/zoo/evaluation/scenarios/straight_pick_lane/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio import gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -10,7 +10,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/straight_straight_1/scenario.py b/zoo/evaluation/scenarios/straight_straight_1/scenario.py index b7e68da6a7..34dfb78eb5 100755 --- a/zoo/evaluation/scenarios/straight_straight_1/scenario.py +++ b/zoo/evaluation/scenarios/straight_straight_1/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio import gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/straight_straight_2/scenario.py b/zoo/evaluation/scenarios/straight_straight_2/scenario.py index d6381e97cf..9bec8c84b9 100755 --- a/zoo/evaluation/scenarios/straight_straight_2/scenario.py +++ b/zoo/evaluation/scenarios/straight_straight_2/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio import gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/straight_turn-left_1/scenario.py b/zoo/evaluation/scenarios/straight_turn-left_1/scenario.py index 03bdcf2ed3..f5d0fb13c1 100755 --- a/zoo/evaluation/scenarios/straight_turn-left_1/scenario.py +++ b/zoo/evaluation/scenarios/straight_turn-left_1/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio import gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/straight_turn-left_2/scenario.py b/zoo/evaluation/scenarios/straight_turn-left_2/scenario.py index 03bdcf2ed3..f5d0fb13c1 100755 --- a/zoo/evaluation/scenarios/straight_turn-left_2/scenario.py +++ b/zoo/evaluation/scenarios/straight_turn-left_2/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio import gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/turn-left_turn-left_1/scenario.py b/zoo/evaluation/scenarios/turn-left_turn-left_1/scenario.py index 41733f6699..cbbe34c855 100755 --- a/zoo/evaluation/scenarios/turn-left_turn-left_1/scenario.py +++ b/zoo/evaluation/scenarios/turn-left_turn-left_1/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio import gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/turn-left_turn-left_2/scenario.py b/zoo/evaluation/scenarios/turn-left_turn-left_2/scenario.py index 41733f6699..cbbe34c855 100755 --- a/zoo/evaluation/scenarios/turn-left_turn-left_2/scenario.py +++ b/zoo/evaluation/scenarios/turn-left_turn-left_2/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio import gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/turn-right_turn-left_1/scenario.py b/zoo/evaluation/scenarios/turn-right_turn-left_1/scenario.py index 3668592f83..333b25129c 100755 --- a/zoo/evaluation/scenarios/turn-right_turn-left_1/scenario.py +++ b/zoo/evaluation/scenarios/turn-right_turn-left_1/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio import gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/turn-right_turn-left_2/scenario.py b/zoo/evaluation/scenarios/turn-right_turn-left_2/scenario.py index 3668592f83..333b25129c 100755 --- a/zoo/evaluation/scenarios/turn-right_turn-left_2/scenario.py +++ b/zoo/evaluation/scenarios/turn-right_turn-left_2/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio import gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/turnleft_pick_lane/scenario.py b/zoo/evaluation/scenarios/turnleft_pick_lane/scenario.py index 94a830f391..cd092088ec 100644 --- a/zoo/evaluation/scenarios/turnleft_pick_lane/scenario.py +++ b/zoo/evaluation/scenarios/turnleft_pick_lane/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio import gen_social_agent_missions +from smarts.sstudio.genscenario import _gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -gen_social_agent_missions( +_gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", From 74d5f49fd71630f9d077e0b7f5f272323ce85afd Mon Sep 17 00:00:00 2001 From: Saul Field Date: Tue, 29 Nov 2022 15:41:43 -0500 Subject: [PATCH 10/19] Warn if gen_* functions called externally. Type fix. --- smarts/sstudio/genscenario.py | 22 +++++++++++++++++++++ ultra/ultra/scenarios/generate_scenarios.py | 4 ++-- 2 files changed, 24 insertions(+), 2 deletions(-) diff --git a/smarts/sstudio/genscenario.py b/smarts/sstudio/genscenario.py index 17a230fac8..0afd49de51 100644 --- a/smarts/sstudio/genscenario.py +++ b/smarts/sstudio/genscenario.py @@ -22,6 +22,7 @@ """ import collections +import inspect import itertools import logging import os @@ -45,6 +46,18 @@ logger.setLevel(logging.WARNING) +def _check_if_called_externally(): + frm = inspect.stack()[2] + mod = inspect.getmodule(frm[0]) + if mod.__name__ != "smarts.sstudio.genscenario": + logger.warning( + "", + exc_info=DeprecationWarning( + "Calling gen_* methods directly is now deprecated. All scenarios must call gen_scenario()." + ), + ) + + def _build_graph(scenario: types.Scenario, base_dir: str) -> Dict[str, Any]: graph = collections.defaultdict(list) @@ -323,6 +336,7 @@ def gen_scenario( def _gen_map(scenario: str, map_spec: types.MapSpec, output_dir: Optional[str] = None): """Saves a map spec to file.""" + _check_if_called_externally() build_dir = os.path.join(scenario, "build") output_dir = os.path.join(output_dir or build_dir, "map") os.makedirs(output_dir, exist_ok=True) @@ -345,6 +359,7 @@ def _gen_traffic( ): """Generates the traffic routes for the given scenario. If the output directory is not provided, the scenario directory is used.""" + _check_if_called_externally() assert name != "missions", "The name 'missions' is reserved for missions!" build_dir = os.path.join(scenario, "build") @@ -386,6 +401,7 @@ def _gen_social_agent_missions( map_spec: An optional map specification that takes precedence over scenario directory information. """ + _check_if_called_externally() # For backwards compatibility we support both a single value and a sequence actors = social_agent_actor @@ -441,6 +457,7 @@ def _gen_agent_missions( map_spec: An optional map specification that takes precedence over scenario directory information. """ + _check_if_called_externally() output_dir = os.path.join(scenario, "build") saved = _gen_missions( @@ -489,6 +506,7 @@ def _gen_group_laps( num_laps: The amount of laps before finishing """ + _check_if_called_externally() start_road_id, start_lane, start_offset = begin end_road_id, end_lane, end_offset = end @@ -531,6 +549,7 @@ def _gen_bubbles(scenario: str, bubbles: Sequence[types.Bubble]): bubbles: The bubbles to add to the scenario. """ + _check_if_called_externally() output_path = os.path.join(scenario, "build", "bubbles.pkl") with open(output_path, "wb") as f: pickle.dump(bubbles, f) @@ -540,6 +559,7 @@ def _gen_friction_map(scenario: str, surface_patches: Sequence[types.RoadSurface """Generates friction map file according to the surface patches defined in scenario file. """ + _check_if_called_externally() output_path = os.path.join(scenario, "build", "friction_map.pkl") with open(output_path, "wb") as f: pickle.dump(surface_patches, f) @@ -558,6 +578,7 @@ def _gen_missions( """Generates a route file to represent missions (a route per mission). Will create the output_dir if it doesn't exist already. """ + _check_if_called_externally() generator = TrafficGenerator(scenario, map_spec) @@ -648,6 +669,7 @@ def _gen_traffic_histories( map_spec: An optional map specification that takes precedence over scenario directory information. """ + _check_if_called_externally() road_map = None # shared across all history_datasets in scenario for hdsr in histories_datasets: assert isinstance(hdsr, types.TrafficHistoryDataset) diff --git a/ultra/ultra/scenarios/generate_scenarios.py b/ultra/ultra/scenarios/generate_scenarios.py index 9e62bcd1cd..e1be42a3d3 100644 --- a/ultra/ultra/scenarios/generate_scenarios.py +++ b/ultra/ultra/scenarios/generate_scenarios.py @@ -40,7 +40,7 @@ import yaml from smarts.core.utils.sumo import sumolib -from smarts.sstudio.genscenario import _gen_bubbles, _gen_missions, _gen_traffic +from smarts.sstudio.genscenario import _gen_agent_missions, _gen_bubbles, _gen_traffic from smarts.sstudio.types import ( Bubble, Distribution, @@ -471,7 +471,7 @@ def generate_left_turn_missions( # Shuffle the missions so agents don't do the same route all the time. if shuffle_missions: random.shuffle(mission_objects) - _gen_missions(scenario, mission_objects) + _gen_agent_missions(scenario, mission_objects) if bubbles: bubble_objects = [ From 44a683a0827f4fe8661b4ea8ed5f9b97f2dbc456 Mon Sep 17 00:00:00 2001 From: Saul Field Date: Tue, 29 Nov 2022 16:52:32 -0500 Subject: [PATCH 11/19] Update docs --- docs/sim/scenario_studio.rst | 35 ++++++++++++++--------------------- smarts/sstudio/genscenario.py | 6 +++--- 2 files changed, 17 insertions(+), 24 deletions(-) diff --git a/docs/sim/scenario_studio.rst b/docs/sim/scenario_studio.rst index 72d4cab0ba..b705dcdacf 100644 --- a/docs/sim/scenario_studio.rst +++ b/docs/sim/scenario_studio.rst @@ -46,8 +46,6 @@ Generate traffic ] ) - gen_traffic(scenario_path, traffic, name="all", output_dir=scenario_path, seed=seed_, overwrite=True) - Note that the `engine` argument to `Traffic` can either be `"SUMO"` or `"SMARTS"`, with `"SUMO"` being the default. As `"SUMO"` can only be used on Sumo-format "road networks", if you need to run SMARTS with another map type you may need to change to the `"SMARTS"` engine. @@ -58,7 +56,7 @@ See more config for `TrafficActor` in :class:`smarts.sstudio.types`. Flow can be used to generate repeated vehicle runs on the same route, you can config vehicle route and depart rate here. -After the `gen_traffic` function is run, a dir named "traffic" containing vehicle config xmls will be created under output_dir. +After the `gen_scenario` function is run, a dir named "traffic" containing vehicle config xmls will be created under output_dir. This a short file example of how it works: @@ -81,33 +79,30 @@ Generate missions ================= The Scenario Studio of SMARTS also allows generation of *missions* for ego agents and social agents. These missions are similar -to routes for social vehicles. When we run `gen_missions`, "missions.rou.xml" file will be created under the output dir: +to routes for social vehicles. When we run `gen_scenario`, "missions.rou.xml" file will be created under the output dir: .. code-block:: python - # agent missions - gen_missions( - scenario, - missions=[Mission(Route(begin=("edge0", 0, "random"), end=("edge1", 0, "max"),)),], - seed=seed_, - ) + missions = [ + Mission(Route(begin=("edge0", 0, "random"), end=("edge1", 0, "max"))), + ] ===================== Generate friction map ===================== -The Scenario Studio of SMARTS also allows generation of *friction map* which consists of a list of *surface patches* for ego agents and social agents. These surface patches are using PositionalZone as in the case of bubbles. When we run `gen_friction_map`, "friction_map.pkl" file will be created under the output dir: +The Scenario Studio of SMARTS also allows generation of *friction map* which consists of a list of *surface patches* for ego agents and social agents. These surface patches are using PositionalZone as in the case of bubbles. When we run `gen_scenario`, "friction_map.pkl" file will be created under the output dir: .. code-block:: python - # friction map - gen_friction_map( - scenario, - surface_patches=[RoadSurfacePatch(PositionalZone(pos=(153, -100), size=(2000, 6000)), - begin_time=0, - end_time=20, - friction_coefficient=0.5)] - ) + friction_maps = [ + RoadSurfacePatch( + PositionalZone(pos=(153, -100), size=(2000, 6000)), + begin_time=0, + end_time=20, + friction_coefficient=0.5, + ), + ] ================= Generate road map @@ -134,8 +129,6 @@ define a `MapSpec` object in your `scenario.py`. map_spec = MapSpec(source="path_or_uri", builder_fn=custom_map_builder) - gen_map(map_spec) - Convert an existing map to SUMO ------------------------------- diff --git a/smarts/sstudio/genscenario.py b/smarts/sstudio/genscenario.py index 0afd49de51..d973cb6ca1 100644 --- a/smarts/sstudio/genscenario.py +++ b/smarts/sstudio/genscenario.py @@ -47,9 +47,9 @@ def _check_if_called_externally(): - frm = inspect.stack()[2] - mod = inspect.getmodule(frm[0]) - if mod.__name__ != "smarts.sstudio.genscenario": + frame_info = inspect.stack()[2] + module = inspect.getmodule(frame_info[0]) + if module.__name__ != "smarts.sstudio.genscenario": logger.warning( "", exc_info=DeprecationWarning( From c480192b27f766b0cde9c1c9a82cd7f4ef42a5d1 Mon Sep 17 00:00:00 2001 From: Saul Field Date: Tue, 29 Nov 2022 17:01:46 -0500 Subject: [PATCH 12/19] Remove ultra files --- .../scenarios/analysis/sumo_experiment.py | 693 ------------------ ultra/ultra/scenarios/generate_scenarios.py | 0 2 files changed, 693 deletions(-) delete mode 100644 ultra/ultra/scenarios/analysis/sumo_experiment.py delete mode 100644 ultra/ultra/scenarios/generate_scenarios.py diff --git a/ultra/ultra/scenarios/analysis/sumo_experiment.py b/ultra/ultra/scenarios/analysis/sumo_experiment.py deleted file mode 100644 index 27c599ebc9..0000000000 --- a/ultra/ultra/scenarios/analysis/sumo_experiment.py +++ /dev/null @@ -1,693 +0,0 @@ -# MIT License -# -# Copyright (C) 2021. Huawei Technologies Co., Ltd. All rights reserved. -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in -# all copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN -# THE SOFTWARE. -import argparse -import os -import sys - -if "SUMO_HOME" in os.environ: - tools = os.path.join(os.environ["SUMO_HOME"], "tools") - sys.path.append(tools) -else: - sys.exit("please declare environment variable 'SUMO_HOME'") - -import time - -import matplotlib.pyplot as plt -import numpy as np - -from ultra.scenarios.generate_scenarios import build_scenarios - -import traci # isort:skip -import traci.constants as tc # isort:skip - - -# sumo -c --remote-port=8813 -# sumo -n map.net.xml -r traffic/all.rou.xml --remote-port=8813 - -# Aggregates information for each edge and lane ... -def edge_lane_data_function(traci, data_aggregator, **kwargs): - if "lane_data" not in data_aggregator: - data_aggregator["lane_data"] = {} - for lane_id in traci.lane.getIDList(): - data_aggregator["lane_data"][lane_id] = { - "num_vehicles": [], - "occupancy": [], - } - if "edge_data" not in data_aggregator: - data_aggregator["edge_data"] = {} - for edge_id in traci.edge.getIDList(): - data_aggregator["edge_data"][edge_id] = { - "num_vehicles": [], - "occupancy": [], - } - - for lane_id in traci.lane.getIDList(): - data_aggregator["lane_data"][lane_id]["num_vehicles"].append( - traci.lane.getLastStepVehicleNumber(lane_id) - ) - data_aggregator["lane_data"][lane_id]["occupancy"].append( - traci.lane.getLastStepOccupancy(lane_id) - ) - for edge_id in traci.edge.getIDList(): - data_aggregator["edge_data"][edge_id]["num_vehicles"].append( - traci.edge.getLastStepVehicleNumber(edge_id) - ) - data_aggregator["edge_data"][edge_id]["occupancy"].append( - traci.edge.getLastStepOccupancy(edge_id) - ) - - -def vehicle_data_function(traci, data_aggregator, blocked_max_speed=0.1, **kwargs): - vehicle_list = traci.vehicle.getIDList() - if "vehicle_data" not in data_aggregator: - data_aggregator["vehicle_data"] = {} - - if "destination" not in data_aggregator: - data_aggregator["destination"] = {} - - if "route" not in data_aggregator: - data_aggregator["route"] = {} - - if "vehicle_density" not in data_aggregator: - data_aggregator["vehicle_density"] = {"All": {}} - - for veh_id in vehicle_list: - if veh_id not in data_aggregator["vehicle_data"]: - veh_route = traci.vehicle.getRoute(veh_id) - data_aggregator["vehicle_density"]["All"][kwargs["last_step"]] = len( - vehicle_list - ) - data_aggregator["vehicle_data"][veh_id] = { - "min_gap": traci.vehicle.getMinGap(veh_id), - "final_target": veh_route[-1], - "origin": veh_route[0], - "destination": veh_route[-1], - "success": False, - "route": veh_route[0] + "|" + veh_route[-1], - "rerouted": None, - "travel_time": 0, - "blocked_time": 0, - "accumulated_blocked_time": 0, - "positions": [], - "lane_list": [], - "last_step": kwargs["last_step"], - } - if veh_route[-1] not in data_aggregator["destination"]: - data_aggregator["destination"][veh_route[-1]] = 1 - else: - data_aggregator["destination"][veh_route[-1]] += 1 - - if veh_route[0] + "|" + veh_route[-1] not in data_aggregator["route"]: - data_aggregator["route"][veh_route[0] + "|" + veh_route[-1]] = 1 - else: - data_aggregator["route"][veh_route[0] + "|" + veh_route[-1]] += 1 - else: - data_aggregator["vehicle_data"][veh_id]["travel_time"] += 1 - data_aggregator["vehicle_data"][veh_id]["positions"].append( - traci.vehicle.getPosition(veh_id) - ) - - if traci.vehicle.getSpeed(veh_id) < blocked_max_speed: - data_aggregator["vehicle_data"][veh_id]["blocked_time"] += 1 - if traci.vehicle.getLeader(veh_id) is None: - data_aggregator["vehicle_data"][veh_id][ - "accumulated_blocked_time" - ] += 1 - else: - data_aggregator["vehicle_data"][veh_id]["accumulated_blocked_time"] = 0 - - if ( - data_aggregator["vehicle_data"][veh_id]["route"] - not in data_aggregator["vehicle_density"] - ): - data_aggregator["vehicle_density"][ - data_aggregator["vehicle_data"][veh_id]["route"] - ] = {} - else: - if ( - not kwargs["last_step"] - in data_aggregator["vehicle_density"][ - data_aggregator["vehicle_data"][veh_id]["route"] - ] - ): - data_aggregator["vehicle_density"][ - data_aggregator["vehicle_data"][veh_id]["route"] - ][kwargs["last_step"]] = 0 - else: - data_aggregator["vehicle_density"][ - data_aggregator["vehicle_data"][veh_id]["route"] - ][kwargs["last_step"]] += 1 - - current_lane = traci.vehicle.getLaneID(veh_id) - if not current_lane in data_aggregator["vehicle_data"][veh_id]["lane_list"]: - data_aggregator["vehicle_data"][veh_id]["lane_list"].append(current_lane) - data_aggregator["vehicle_data"][veh_id][ - "current_edge" - ] = traci.vehicle.getRoadID(veh_id) - if ( - data_aggregator["vehicle_data"][veh_id]["current_edge"] - == data_aggregator["vehicle_data"][veh_id]["final_target"] - ): - data_aggregator["vehicle_data"][veh_id]["success"] = True - - -def sumo_rerouting_routine( - traci, data_aggregator, time_elapsed_until_reroute=20, **kwargs -): - vehicle_list = traci.vehicle.getIDList() - for veh_id in vehicle_list: - vehicle_lane_index = traci.vehicle.getLaneIndex(veh_id) - bestLanes = traci.vehicle.getBestLanes(veh_id) - if not bestLanes[vehicle_lane_index][4] and len(bestLanes) > 1: - - selected_lanes = [] - for j in range(len(bestLanes)): - if j != vehicle_lane_index: - selected_lanes.append(j) - - select_lane = np.random.choice(selected_lanes) - if select_lane > vehicle_lane_index: - direction = 1 - else: - direction = -1 - - # Is changing lane, locked, and is leader of the lane -> Reroute - if ( - not traci.vehicle.couldChangeLane(veh_id, direction) - and data_aggregator["vehicle_data"][veh_id]["accumulated_blocked_time"] - > time_elapsed_until_reroute - and traci.vehicle.getLeader(veh_id) is None - ): - origin = data_aggregator["vehicle_data"][veh_id]["origin"].split("-")[1] - final_target = data_aggregator["vehicle_data"][veh_id][ - "final_target" - ].split("-")[1] - # print(origin, final_target) - potential_list = [] - for potential_reroute_target in data_aggregator["destination"]: - token = potential_reroute_target.split("-")[1] - if token != final_target and token != origin: - potential_list.append(potential_reroute_target) - result = np.random.choice(potential_list) - try: - # traci.vehicle.changeTarget(veh_id, result) - new_route = list( - traci.simulation.findRoute( - data_aggregator["vehicle_data"][veh_id]["current_edge"], - result, - ).edges - ) - traci.vehicle.setRoute(veh_id, new_route) - print("Route Change Success") - data_aggregator["vehicle_data"][veh_id][ - "accumulated_blocked_time" - ] = 0 - data_aggregator["vehicle_data"][veh_id]["rerouted"] = result - except: - print("Route Change Failed") - - -def generate_figures( - data, - figure_dir, - setting_id, - failure_rate, - num_steps, - num_bins=50, - comparisons=[[("route", "avg_blocked_time"), ("route", "failure_rate")]], -): - # default_statistics = {"blocked_time":[], "travel_time":[], "success":0, "rerouted":0, "in_simulation":0} - total_travel_time_list = [] - travel_percentile_list = [] - blocked_travel_time_list = [] - num_vehicle_list = [] - statistics_list = [] - failed_list = [] - num_scenarios = len(data) - num_bins = min(num_scenarios // 2, num_bins) - for scenario in data: - statistics = { - "destination": {}, - "route": {}, - "vehicle_gen_prob": scenario["vehicle_gen_prob"], - } - scenario_travel_time = [] - scenario_blocked_time = [] - for veh_id in scenario["vehicle_data"]: - destination_key = scenario["vehicle_data"][veh_id]["destination"] - route_key = scenario["vehicle_data"][veh_id]["route"] - - is_successful = scenario["vehicle_data"][veh_id]["success"] - is_rerouted = not scenario["vehicle_data"][veh_id]["rerouted"] is None - is_still_running = not is_successful and not is_rerouted - travel_time = scenario["vehicle_data"][veh_id]["travel_time"] - blocked_time = scenario["vehicle_data"][veh_id]["blocked_time"] - has_failed = travel_time > failure_rate or is_rerouted - - if not destination_key in statistics["destination"]: - statistics["destination"][destination_key] = { - "blocked_time": [], - "travel_time": [], - "success": 0, - "rerouted": 0, - "in_simulation": 0, - "deadlock_rate": 0, - "num_vehicles": 0, - } - if not route_key in statistics["route"]: - statistics["route"][route_key] = { - "blocked_time": [], - "travel_time": [], - "success": 0, - "rerouted": 0, - "in_simulation": 0, - "deadlock_rate": 0, - "num_vehicles": 0, - } - - statistics["destination"][destination_key]["success"] += int(is_successful) - statistics["destination"][destination_key]["rerouted"] += int(is_rerouted) - statistics["destination"][destination_key]["in_simulation"] += int( - is_still_running - ) - statistics["destination"][destination_key]["deadlock_rate"] += int( - has_failed - ) - statistics["destination"][destination_key]["num_vehicles"] += 1 - - statistics["destination"][destination_key]["travel_time"].append( - travel_time - ) - statistics["destination"][destination_key]["blocked_time"].append( - blocked_time - ) - - statistics["route"][route_key]["success"] += int(is_successful) - statistics["route"][route_key]["rerouted"] += int(is_rerouted) - statistics["route"][route_key]["in_simulation"] += int(is_still_running) - statistics["route"][route_key]["deadlock_rate"] += int(has_failed) - statistics["route"][route_key]["num_vehicles"] += 1 - - statistics["route"][route_key]["travel_time"].append(travel_time) - statistics["route"][route_key]["blocked_time"].append(blocked_time) - - travel_time_list = [] - blocked_time_list = [] - scenario_failed = 0 - for destination_key in statistics["destination"]: - travel_time_list.extend( - statistics["destination"][destination_key]["travel_time"] - ) - blocked_time_list.extend( - statistics["destination"][destination_key]["blocked_time"] - ) - scenario_failed += statistics["destination"][destination_key][ - "deadlock_rate" - ] - - scenario_99_percentile_travel_time = np.percentile(travel_time_list, 99) - scenario_total_travel_time = np.mean(travel_time_list) - scenario_blocked_time = np.mean(blocked_time_list) - - total_travel_time_list.append(scenario_total_travel_time) - travel_percentile_list.append(scenario_99_percentile_travel_time) - blocked_travel_time_list.append(scenario_blocked_time) - - failed_list.append(scenario_failed / max(len(scenario["vehicle_data"]), 1)) - num_vehicle_list.append(len(scenario["vehicle_data"])) - statistics_list.append(statistics) - - index = 0 - for scenario in data: - statistics = statistics_list[index] - scenario_statistics = {} - route_list = list(scenario["vehicle_density"].keys()) - for route_id in route_list: - scenario_statistics[route_id] = [] - for i in range(num_steps): - for route_id in route_list: - if not i in scenario["vehicle_density"][route_id]: - scenario["vehicle_density"][route_id][i] = 0 - scenario_statistics[route_id].append( - scenario["vehicle_density"][route_id][i] - ) - for route_id in route_list: - scenario_statistics[route_id] = np.mean(scenario_statistics[route_id]) - statistics["vehicle_density"] = scenario_statistics - index += 1 - - # Append all scenario statistics together - all_statistics = { - "destination": {}, - "route": {}, - "vehicle_density": {}, - "vehicle_gen_prob": {}, - } - all_statistics["route"]["All"] = { - "avg_blocked_time": blocked_travel_time_list, - "avg_travel_time": total_travel_time_list, - "deadlock_rate": failed_list, - "num_vehicles": num_vehicle_list, - } - - for scenario_statistics in statistics_list: - for destination_key in scenario_statistics["destination"]: - if not destination_key in all_statistics["destination"]: - all_statistics["destination"][destination_key] = { - "blocked_time": [], - "travel_time": [], - "success": [], - "rerouted": [], - "in_simulation": [], - "deadlock_rate": [], - "num_vehicles": [], - } - all_statistics["destination"][destination_key]["success"].append( - scenario_statistics["destination"][destination_key]["success"] - ) - all_statistics["destination"][destination_key]["rerouted"].append( - scenario_statistics["destination"][destination_key]["rerouted"] - ) - all_statistics["destination"][destination_key]["in_simulation"].append( - scenario_statistics["destination"][destination_key]["in_simulation"] - ) - all_statistics["destination"][destination_key]["travel_time"].extend( - scenario_statistics["destination"][destination_key]["travel_time"] - ) - all_statistics["destination"][destination_key]["blocked_time"].extend( - scenario_statistics["destination"][destination_key]["blocked_time"] - ) - - all_statistics["destination"][destination_key]["deadlock_rate"].append( - scenario_statistics["destination"][destination_key]["deadlock_rate"] - / max( - scenario_statistics["destination"][destination_key]["num_vehicles"], - 1, - ) - ) - all_statistics["destination"][destination_key]["num_vehicles"].append( - scenario_statistics["destination"][destination_key]["num_vehicles"] - ) - - for route_key in scenario_statistics["route"]: - if not route_key in all_statistics["route"]: - all_statistics["route"][route_key] = { - "blocked_time": [], - "travel_time": [], - "avg_travel_time": [], - "avg_blocked_time": [], - "success": [], - "rerouted": [], - "in_simulation": [], - "deadlock_rate": [], - "num_vehicles": [], - } - all_statistics["route"][route_key]["success"].append( - scenario_statistics["route"][route_key]["success"] - ) - all_statistics["route"][route_key]["rerouted"].append( - scenario_statistics["route"][route_key]["rerouted"] - ) - all_statistics["route"][route_key]["in_simulation"].append( - scenario_statistics["route"][route_key]["in_simulation"] - ) - all_statistics["route"][route_key]["travel_time"].extend( - scenario_statistics["route"][route_key]["travel_time"] - ) - all_statistics["route"][route_key]["blocked_time"].extend( - scenario_statistics["route"][route_key]["blocked_time"] - ) - - all_statistics["route"][route_key]["avg_travel_time"].append( - np.mean(scenario_statistics["route"][route_key]["travel_time"]) - ) - all_statistics["route"][route_key]["avg_blocked_time"].append( - np.mean(scenario_statistics["route"][route_key]["blocked_time"]) - ) - - all_statistics["route"][route_key]["deadlock_rate"].append( - scenario_statistics["route"][route_key]["deadlock_rate"] - / max(scenario_statistics["route"][route_key]["num_vehicles"], 1) - ) - all_statistics["route"][route_key]["num_vehicles"].append( - scenario_statistics["route"][route_key]["num_vehicles"] - ) - for route_key in scenario_statistics["vehicle_density"]: - if route_key not in all_statistics["vehicle_density"]: - all_statistics["vehicle_density"][route_key] = {"vehicle_density": []} - all_statistics["vehicle_density"][route_key]["vehicle_density"].append( - scenario_statistics["vehicle_density"][route_key] - ) - - for route_key in scenario_statistics["vehicle_gen_prob"]: - if route_key not in all_statistics["vehicle_gen_prob"]: - all_statistics["vehicle_gen_prob"][route_key] = {"vehicle_gen_prob": []} - all_statistics["vehicle_gen_prob"][route_key]["vehicle_gen_prob"].append( - scenario_statistics["vehicle_gen_prob"][route_key] - ) - # For each destination and route, we generate 5 histogram .... + 2 for the travel time and percentile ... - try: - os.mkdir(figure_dir) - except: - print("Directories already exists ... ") - figure_dir = figure_dir + "/" + setting_id - try: - os.mkdir(figure_dir) - except: - print("Directories already exists ... ") - - for overarching_key in all_statistics: - for data_key in all_statistics[overarching_key]: - sub_figure_dir = figure_dir + "/" + data_key - try: - os.mkdir(sub_figure_dir) - except: - print("Directories already exists ... ") - for statistics_key in all_statistics[overarching_key][data_key]: - n, bins, patches = plt.hist( - all_statistics[overarching_key][data_key][statistics_key], - num_bins, - facecolor="blue", - ) - plt.title( - "Histogram Edge/Route_" + str(data_key) + "_" + str(statistics_key) - ) - plt.xlabel(statistics_key) - plt.ylabel( - "Number of occurences for " + str(num_scenarios) + " scenarios" - ) - plt.savefig(sub_figure_dir + "/" + statistics_key + ".png") - plt.close() - - # collect key informations - for i in range(len(comparisons)): - comparison = comparisons[i] - key_00 = comparison[0][0] - key_10 = comparison[1][0] - key_01 = comparison[0][1] - key_11 = comparison[1][1] - print(comparison) - id_list = list(all_statistics[key_00]) - for key_id in id_list: - set_1 = all_statistics[key_00][key_id][key_01] - set_2 = all_statistics[key_10][key_id][key_11] - if len(set_1) == len(set_2): - plt.plot(set_1, set_2, ".") - plt.title(key_01 + " vs " + key_11) - plt.xlabel(key_01) - plt.ylabel(key_11) - plt.savefig(figure_dir + "/" + key_id + "/" + key_01 + " vs " + key_11) - plt.close() - else: - print("Invalid Comparison") - - -def sumo_traci_runner( - simulation_time, - custom_traci_functions, - num_iterations, - scenario_dir, - simulation_step_size=1, - init_time_skip=50, - seed=0, - run_per_scenario=2, - **kwargs, -): - skip = int(1 / simulation_step_size) - np.random.seed(seed) - all_simulation_data = [] - traci.init(8813) - task = kwargs["task"] - level = kwargs["level"] - print(task, level) - - def dynamic_vehicle_gen_probability_func(pattern, current_step): - if kwargs["vehicle_gen_prob"] > 0: - current_step = current_step // run_per_scenario - for edge_id in pattern["routes"]: - if pattern["routes"][edge_id] is None: - continue - pattern["routes"][edge_id]["begin_time_init"]["params"][ - "probability" - ] = ( - kwargs["vehicle_gen_prob"] - + current_step * kwargs["dynamic_vehicle_gen_prob"] - ) - return pattern - - build_scenarios( - task=f"task{task}", - level_name=level, - num_seeds=num_iterations * run_per_scenario, - has_stopwatcher=False, - dynamic_pattern_func=dynamic_vehicle_gen_probability_func, - ) - for j in range(num_iterations * run_per_scenario): - current_time = time.time() - current_scenario_dir = scenario_dir + "-flow-" + str(j) - current_vehicle_gen_prob = ( - kwargs["vehicle_gen_prob"] - + j // run_per_scenario * kwargs["dynamic_vehicle_gen_prob"] - ) - # for k in range(run_per_scenario): - # # Reset scenario - traci.load( - [ - "-n", - current_scenario_dir + "/map.net.xml", - "-r", - current_scenario_dir + "/build/traffic/all.rou.xml", - "--seed", - str(np.random.randint(0, run_per_scenario)), - ] - ) - simulation_data = {} # Dictionary object to collect data ... - accumulated_time = 0 - for i in range(int((simulation_time + init_time_skip) / simulation_step_size)): - accumulated_time += simulation_step_size - traci.simulationStep(accumulated_time) # One step to initialize everything - if i > int(init_time_skip / simulation_step_size) and i % skip == 0: - # print("Sim:", j, "Sim Seed:", k,"Time Step:", traci.simulation.getTime(), "Num Vehicles:", len(traci.vehicle.getIDList())) - for func in custom_traci_functions: - func( - traci, - simulation_data, - last_step=i - init_time_skip - 1, - **kwargs, - ) - - simulation_data["vehicle_gen_prob"] = {"All": current_vehicle_gen_prob} - for route_id in simulation_data["route"]: - simulation_data["vehicle_gen_prob"][route_id] = current_vehicle_gen_prob - - all_simulation_data.append(simulation_data) - print( - "Sim:", - j, - "with", - run_per_scenario, - "seeds, completed with", - time.time() - current_time, - "seconds", - ) - traci.close() - # Reached End of simulation ... - return all_simulation_data - - -# Default sumo instruction for 4 lane_t -# sumo -n research/edmonton/intersections/scenarios/task1/hard_4lane_t_80kmh_heavy_traffic_stress_test_t_intersection-mission-0-flow-0/map.net.xml -r research/edmonton/intersections/scenarios/task1/hard_4lane_t_80kmh_heavy_traffic_stress_test_t_intersection-mission-0-flow-0/build/traffic/all.rou.xml --remote-port=8813 -# Run command example -# python research/edmonton/intersections/scenarios/sumo_experiment.py --level="hard" --task="1" --scenario_dir="research/edmonton/intersections/scenarios/task1/hard_4lane_t_80kmh_heavy_traffic_stress_test_t_intersection-mission-0" --figure_dir="research/edmonton/intersections/scenarios/task1/figures" --setting_id="hard_t_intersection_4_vehicle_prob_0_05" --num_scenario=100 -if __name__ == "__main__": - parser = argparse.ArgumentParser("generate scenarios") - parser.add_argument("--task", help="type a task id [0, 1, 2, 3]", type=str) - parser.add_argument("--level", help="easy/medium/hard", type=str) - parser.add_argument("--scenario_dir", help="path", type=str) - parser.add_argument("--figure_dir", help="path", type=str) - parser.add_argument( - "--dynamic_vehicle_gen_prob", help="path", type=float, default=0 - ) - parser.add_argument("--vehicle_gen_prob", help="path", type=float, default=0.05) - parser.add_argument("--run_per_scenario", help="path", type=int, default=3) - - parser.add_argument( - "--setting_id", - help="for identifying figures", - type=str, - default="hard_t_intersection_0_05", - ) - parser.add_argument("--reroute", help="path", type=str, default="False") - parser.add_argument("--num_scenario", help="path", type=int, default=5) - parser.add_argument("--scenario_run_time", help="path", type=int, default=1200) - parser.add_argument("--failure_time", help="path", type=int, default=600) - - args = parser.parse_args() - if args.level not in [ - "easy", - "medium", - "hard", - ]: - raise ValueError('level not accepted select from ["easy", "medium", "hard"]') - if args.reroute == "True": - sim_funcs = [ - edge_lane_data_function, - vehicle_data_function, - sumo_rerouting_routine, - ] - else: - sim_funcs = [edge_lane_data_function, vehicle_data_function] - data = sumo_traci_runner( - args.scenario_run_time, - sim_funcs, - args.num_scenario, - args.scenario_dir, - task=args.task, - level=args.level, - vehicle_gen_prob=args.vehicle_gen_prob, - dynamic_vehicle_gen_prob=args.dynamic_vehicle_gen_prob, - run_per_scenario=args.run_per_scenario, - ) - comparisons = [ - [("route", "avg_blocked_time"), ("route", "deadlock_rate")], - [("vehicle_density", "vehicle_density"), ("route", "deadlock_rate")], - [("vehicle_density", "vehicle_density"), ("route", "avg_travel_time")], - [("vehicle_density", "vehicle_density"), ("route", "avg_blocked_time")], - [("vehicle_gen_prob", "vehicle_gen_prob"), ("route", "avg_blocked_time")], - [("vehicle_gen_prob", "vehicle_gen_prob"), ("route", "deadlock_rate")], - [ - ("vehicle_gen_prob", "vehicle_gen_prob"), - ("vehicle_density", "vehicle_density"), - ], - ] - generate_figures( - data, - args.figure_dir, - args.setting_id - + "_reroute_" - + str(args.reroute) - + "_failure_time_" - + str(args.failure_time), - args.failure_time, - args.scenario_run_time, - comparisons=comparisons, - ) diff --git a/ultra/ultra/scenarios/generate_scenarios.py b/ultra/ultra/scenarios/generate_scenarios.py deleted file mode 100644 index e69de29bb2..0000000000 From afda06f9d2ae49c7a15d847f00d6e315e325a5d2 Mon Sep 17 00:00:00 2001 From: Saul Field Date: Wed, 30 Nov 2022 17:47:54 -0500 Subject: [PATCH 13/19] Fix overwrite issue --- scenarios/open_drive/od_4lane/scenario.py | 1 - scenarios/open_drive/od_merge/scenario.py | 1 - scenarios/open_drive/od_newmarket/scenario.py | 1 - smarts/sstudio/genscenario.py | 9 ++++----- smarts/waymo/README.md | 1 - 5 files changed, 4 insertions(+), 9 deletions(-) diff --git a/scenarios/open_drive/od_4lane/scenario.py b/scenarios/open_drive/od_4lane/scenario.py index c159ee10ff..d8b650194c 100644 --- a/scenarios/open_drive/od_4lane/scenario.py +++ b/scenarios/open_drive/od_4lane/scenario.py @@ -6,5 +6,4 @@ gen_scenario( Scenario(), output_dir=str(Path(__file__).parent), - overwrite=True, ) diff --git a/scenarios/open_drive/od_merge/scenario.py b/scenarios/open_drive/od_merge/scenario.py index dbe185899c..405799f671 100644 --- a/scenarios/open_drive/od_merge/scenario.py +++ b/scenarios/open_drive/od_merge/scenario.py @@ -10,5 +10,4 @@ ego_missions=ego_missions, ), output_dir=str(Path(__file__).parent), - overwrite=True, ) diff --git a/scenarios/open_drive/od_newmarket/scenario.py b/scenarios/open_drive/od_newmarket/scenario.py index c159ee10ff..d8b650194c 100644 --- a/scenarios/open_drive/od_newmarket/scenario.py +++ b/scenarios/open_drive/od_newmarket/scenario.py @@ -6,5 +6,4 @@ gen_scenario( Scenario(), output_dir=str(Path(__file__).parent), - overwrite=True, ) diff --git a/smarts/sstudio/genscenario.py b/smarts/sstudio/genscenario.py index d973cb6ca1..9199bedc60 100644 --- a/smarts/sstudio/genscenario.py +++ b/smarts/sstudio/genscenario.py @@ -141,7 +141,6 @@ def gen_scenario( scenario: types.Scenario, output_dir: Union[str, Path], seed: int = 42, - overwrite: bool = False, ): """This is now the preferred way to generate a scenario. Instead of calling the gen_* methods directly, we provide this higher-level abstraction that takes care @@ -230,7 +229,7 @@ def gen_scenario( traffic=traffic, name=name, seed=seed, - overwrite=overwrite, + overwrite=True, map_spec=map_spec, ) _update_artifacts(db_conn, artifact_paths, obj_hash) @@ -254,7 +253,7 @@ def gen_scenario( vehicle_count=mission.actor_count, num_laps=mission.num_laps, seed=seed, - overwrite=overwrite, + overwrite=True, map_spec=map_spec, ) else: @@ -265,7 +264,7 @@ def gen_scenario( scenario=output_dir, missions=missions, seed=seed, - overwrite=overwrite, + overwrite=True, map_spec=map_spec, ) @@ -328,7 +327,7 @@ def gen_scenario( _gen_traffic_histories( scenario=output_dir, histories_datasets=scenario.traffic_histories, - overwrite=overwrite, + overwrite=True, map_spec=map_spec, ) _update_artifacts(db_conn, artifact_paths, obj_hash) diff --git a/smarts/waymo/README.md b/smarts/waymo/README.md index 9c5e18415c..da147e7a20 100644 --- a/smarts/waymo/README.md +++ b/smarts/waymo/README.md @@ -181,7 +181,6 @@ Commands you can execute at this level: traffic_histories=[traffic_history], ), output_dir=str(Path(__file__).parent), - overwrite=True, ) ``` And `/waymo.yaml` for generating history dataset and imitation learning aspects of `SMARTS`: From 27aeb54637247a5ab6de8823896872cbf5f36855 Mon Sep 17 00:00:00 2001 From: Saul Field Date: Fri, 9 Dec 2022 15:47:19 -0500 Subject: [PATCH 14/19] Apply suggestions from code review Co-authored-by: Tucker Alban --- docs/sim/scenario_studio.rst | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/sim/scenario_studio.rst b/docs/sim/scenario_studio.rst index b705dcdacf..37a97ad19d 100644 --- a/docs/sim/scenario_studio.rst +++ b/docs/sim/scenario_studio.rst @@ -56,7 +56,7 @@ See more config for `TrafficActor` in :class:`smarts.sstudio.types`. Flow can be used to generate repeated vehicle runs on the same route, you can config vehicle route and depart rate here. -After the `gen_scenario` function is run, a dir named "traffic" containing vehicle config xmls will be created under output_dir. +After `traffic` is provided to the `gen_scenario` function, a dir named "traffic" will be created under output_dir which contains background vehicle and route definitions. This a short file example of how it works: @@ -91,7 +91,7 @@ to routes for social vehicles. When we run `gen_scenario`, "missions.rou.xml" fi Generate friction map ===================== -The Scenario Studio of SMARTS also allows generation of *friction map* which consists of a list of *surface patches* for ego agents and social agents. These surface patches are using PositionalZone as in the case of bubbles. When we run `gen_scenario`, "friction_map.pkl" file will be created under the output dir: +The Scenario Studio of SMARTS also allows the generation of a *friction map* which consists of a list of *surface patches* for ego agents and social agents. These surface patches are using PositionalZone as in the case of bubbles. When we run `gen_scenario` passing in `friction_maps`, a "friction_map.pkl" file will be created under the output dir: .. code-block:: python From 19cd6bb73387903f7ca01d80c57ed95e1ce4e8ac Mon Sep 17 00:00:00 2001 From: Saul Field Date: Fri, 9 Dec 2022 15:48:26 -0500 Subject: [PATCH 15/19] Update changelog --- CHANGELOG.md | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 0261410e7f..d2d0eb2fe1 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -50,7 +50,10 @@ Copy and pasting the git commit messages is __NOT__ enough. - Renamed `examples/history_vehicles_replacement_for_imitation_learning.py` to `examples/traffic_histories_vehicle_replacement.py`. - `SumoTrafficSimulation` will now try to hand-off the vehicles it controls to the new SMARTS background traffic provider by default if the Sumo provider crashes. - SMARTS now gives an error about a suspected lack of junction edges in sumo maps on loading of them. -- Substantial changes to scenario builds to make scenario iteration faster. Scenario build artifacts are now cached and built incrementally, meaning that subsequent builds (without the `clean` option) will only build the artifacts that depend on the changed DSL objects. All build artifacts are now in a local `build/` directory in each scenario's directory. NOTE: the `allow_offset_map` option has been removed. This must now be set in a `MapSpec` object in the scenario.py if this option is needed. Another requirement is that all scenarios must have a `scenario.py`, and must call `gen_scenario()`, rather than the individual `gen_` functions, which are now private. +- Scenario build artifacts are now cached and built incrementally, meaning that subsequent builds (without the `clean` option) will only build the artifacts that depend on the changed DSL objects +- All build artifacts are now in a local `build/` directory in each scenario's directory +- The `allow_offset_map` option has been removed. This must now be set in a `MapSpec` object in the scenario.py if this option is needed +- All scenarios must have a `scenario.py`, and must call `gen_scenario()`, rather than the individual `gen_` functions, which are now private ### Removed - Removed support for deprecated json-based and YAML formats for traffic histories. From 31d96340963469458a649abe3ce351f2e8b817c1 Mon Sep 17 00:00:00 2001 From: Saul Field Date: Fri, 9 Dec 2022 16:15:57 -0500 Subject: [PATCH 16/19] Update scenarios --- .../intersections/2lane_circle/scenario.py | 50 ++++++++----- scenarios/sumo/zoo_intersection/scenario.py | 71 ++++++++----------- 2 files changed, 62 insertions(+), 59 deletions(-) diff --git a/scenarios/sumo/intersections/2lane_circle/scenario.py b/scenarios/sumo/intersections/2lane_circle/scenario.py index 243fd2aa66..5295dcb110 100644 --- a/scenarios/sumo/intersections/2lane_circle/scenario.py +++ b/scenarios/sumo/intersections/2lane_circle/scenario.py @@ -1,15 +1,13 @@ -import os +from pathlib import Path -from smarts.sstudio.genscenario import _gen_social_agent_missions -from smarts.sstudio.types import Mission, Route, SocialAgentActor +import smarts.sstudio.types as t +from smarts.sstudio import gen_scenario -scenario = os.path.dirname(os.path.realpath(__file__)) - -laner_agent = SocialAgentActor( +laner_agent = t.SocialAgentActor( name="laner-agent", agent_locator="scenarios.sumo.intersections.2lane_circle.agent_prefabs:laner-agent-v0", ) -buddha_agent = SocialAgentActor( +buddha_agent = t.SocialAgentActor( name="buddha-agent", agent_locator="scenarios.sumo.intersections.2lane_circle.agent_prefabs:buddha-agent-v0", ) @@ -36,16 +34,30 @@ # }, # ) -_gen_social_agent_missions( - scenario, - social_agent_actor=laner_agent, - name=f"s-agent-{laner_agent.name}", - missions=[Mission(Route(begin=("edge-east-EW", 0, 5), end=("edge-west-EW", 0, 5)))], -) - -_gen_social_agent_missions( - scenario, - social_agent_actor=buddha_agent, - name=f"s-agent-{buddha_agent.name}", - missions=[Mission(Route(begin=("edge-west-WE", 0, 5), end=("edge-east-WE", 0, 5)))], +gen_scenario( + scenario=t.Scenario( + social_agent_missions={ + f"s-agent-{laner_agent.name}": ( + [laner_agent], + [ + t.Mission( + t.Route( + begin=("edge-east-EW", 0, 5), end=("edge-west-EW", 0, 5) + ) + ) + ], + ), + f"s-agent-{buddha_agent.name}": ( + [buddha_agent], + [ + t.Mission( + t.Route( + begin=("edge-west-WE", 0, 5), end=("edge-east-WE", 0, 5) + ) + ) + ], + ), + } + ), + output_dir=Path(__file__).parent, ) diff --git a/scenarios/sumo/zoo_intersection/scenario.py b/scenarios/sumo/zoo_intersection/scenario.py index 5387930a3a..b10fd43587 100644 --- a/scenarios/sumo/zoo_intersection/scenario.py +++ b/scenarios/sumo/zoo_intersection/scenario.py @@ -1,11 +1,7 @@ -import os import random +from pathlib import Path -from smarts.sstudio.genscenario import ( - _gen_agent_missions, - _gen_social_agent_missions, - _gen_traffic, -) +from smarts.sstudio import gen_scenario from smarts.sstudio.types import ( Distribution, EndlessMission, @@ -14,13 +10,12 @@ Mission, RandomRoute, Route, + Scenario, SocialAgentActor, Traffic, TrafficActor, ) -scenario = os.path.dirname(os.path.realpath(__file__)) - # Traffic Vehicles # car = TrafficActor( @@ -43,11 +38,12 @@ turn_left_routes = [("east-EW", "south-NS")] turn_right_routes = [("west-WE", "south-NS")] +traffic = {} for name, routes in { "horizontal": horizontal_routes, "turns": turn_left_routes + turn_right_routes, }.items(): - traffic = Traffic( + traffic[name] = Traffic( flows=[ Flow( route=Route( @@ -61,14 +57,6 @@ ] ) - for seed in [0, 5]: - _gen_traffic( - scenario, - traffic, - name=f"{name}-{seed}", - seed=seed, - ) - # Social Agents # @@ -87,28 +75,31 @@ initial_speed=20, ) -_gen_social_agent_missions( - scenario, - social_agent_actor=social_agent2, - name=f"s-agent-{social_agent2.name}", - missions=[Mission(RandomRoute())], -) - -_gen_social_agent_missions( - scenario, - social_agent_actor=social_agent1, - name=f"s-agent-{social_agent1.name}", - missions=[ - EndlessMission(begin=("edge-south-SN", 0, 30)), - Mission(Route(begin=("edge-west-WE", 0, 10), end=("edge-east-WE", 0, 10))), - ], -) -# Agent Missions -_gen_agent_missions( - scenario=scenario, - missions=[ - Mission(Route(begin=("edge-east-EW", 0, 10), end=("edge-south-NS", 0, 10))), - Mission(Route(begin=("edge-south-SN", 0, 10), end=("edge-east-WE", 0, 10))), - ], +gen_scenario( + scenario=Scenario( + traffic=traffic, + ego_missions=[ + Mission(Route(begin=("edge-east-EW", 0, 10), end=("edge-south-NS", 0, 10))), + Mission(Route(begin=("edge-south-SN", 0, 10), end=("edge-east-WE", 0, 10))), + ], + social_agent_missions={ + f"s-agent-{social_agent2.name}": ( + [social_agent2], + [Mission(RandomRoute())], + ), + f"s-agent-{social_agent1.name}": ( + [social_agent1], + [ + EndlessMission(begin=("edge-south-SN", 0, 30)), + Mission( + Route( + begin=("edge-west-WE", 0, 10), end=("edge-east-WE", 0, 10) + ) + ), + ], + ), + }, + ), + output_dir=Path(__file__).parent, ) From 85f72dda4f66a6f4d314431aa6adfff4f1ce0adf Mon Sep 17 00:00:00 2001 From: Saul Field Date: Tue, 13 Dec 2022 18:58:17 -0500 Subject: [PATCH 17/19] Changes from review --- smarts/sstudio/genhistories.py | 4 ---- smarts/sstudio/genscenario.py | 31 ++----------------------------- 2 files changed, 2 insertions(+), 33 deletions(-) diff --git a/smarts/sstudio/genhistories.py b/smarts/sstudio/genhistories.py index 0eacf03050..7706a758fb 100644 --- a/smarts/sstudio/genhistories.py +++ b/smarts/sstudio/genhistories.py @@ -992,7 +992,6 @@ def column_val_in_row(self, row, col_name: str) -> Any: def import_dataset( dataset_spec: types.TrafficHistoryDataset, output_path: str, - overwrite: bool, map_bbox: Optional[BoundingBox] = None, ): """called to pre-process (import) a TrafficHistoryDataset for use by SMARTS""" @@ -1001,9 +1000,6 @@ def import_dataset( return output = os.path.join(output_path, f"{dataset_spec.name}.shf") if os.path.exists(output): - if not overwrite: - print(f"file already exists at {output}. skipping...") - return os.remove(output) source = dataset_spec.source_type dataset_dict = dataset_spec.__dict__ diff --git a/smarts/sstudio/genscenario.py b/smarts/sstudio/genscenario.py index 9199bedc60..d35dae40f4 100644 --- a/smarts/sstudio/genscenario.py +++ b/smarts/sstudio/genscenario.py @@ -229,7 +229,6 @@ def gen_scenario( traffic=traffic, name=name, seed=seed, - overwrite=True, map_spec=map_spec, ) _update_artifacts(db_conn, artifact_paths, obj_hash) @@ -253,7 +252,6 @@ def gen_scenario( vehicle_count=mission.actor_count, num_laps=mission.num_laps, seed=seed, - overwrite=True, map_spec=map_spec, ) else: @@ -264,7 +262,6 @@ def gen_scenario( scenario=output_dir, missions=missions, seed=seed, - overwrite=True, map_spec=map_spec, ) @@ -293,7 +290,6 @@ def gen_scenario( scenario=output_dir, social_agent_actor=actors, missions=missions, - seed=seed, map_spec=map_spec, ) @@ -327,7 +323,6 @@ def gen_scenario( _gen_traffic_histories( scenario=output_dir, histories_datasets=scenario.traffic_histories, - overwrite=True, map_spec=map_spec, ) _update_artifacts(db_conn, artifact_paths, obj_hash) @@ -353,7 +348,6 @@ def _gen_traffic( name: str, output_dir: Optional[str] = None, seed: int = 42, - overwrite: bool = False, map_spec: Optional[types.MapSpec] = None, ): """Generates the traffic routes for the given scenario. If the output directory is @@ -365,7 +359,7 @@ def _gen_traffic( output_dir = os.path.join(output_dir or build_dir, "traffic") os.makedirs(output_dir, exist_ok=True) - generator = TrafficGenerator(scenario, map_spec, overwrite=overwrite) + generator = TrafficGenerator(scenario, map_spec, overwrite=True) saved_path = generator.plan_and_save(traffic, name, output_dir, seed=seed) if saved_path: @@ -377,8 +371,6 @@ def _gen_social_agent_missions( missions: Sequence[types.Mission], social_agent_actor: Union[types.SocialAgentActor, Sequence[types.SocialAgentActor]], name: str, - seed: int = 42, - overwrite: bool = False, map_spec: Optional[types.MapSpec] = None, ): """Generates the social agent missions for the given scenario. @@ -395,8 +387,6 @@ def _gen_social_agent_missions( of the social agent traffic file seed: The random seed to use when generating behavior - overwrite: - If to forcefully write over the previous existing output file map_spec: An optional map specification that takes precedence over scenario directory information. """ @@ -425,8 +415,6 @@ def _gen_social_agent_missions( actors=actors, name=name, output_dir=output_dir, - seed=seed, - overwrite=overwrite, map_spec=map_spec, ) @@ -438,7 +426,6 @@ def _gen_agent_missions( scenario: str, missions: Sequence, seed: int = 42, - overwrite: bool = False, map_spec: Optional[types.MapSpec] = None, ): """Generates a route file to represent missions (a route per mission). Will create @@ -451,8 +438,6 @@ def _gen_agent_missions( A sequence of missions for social agents to perform seed: The random seed to use when generating behavior - overwrite: - If to forcefully write over the previous existing output file map_spec: An optional map specification that takes precedence over scenario directory information. """ @@ -465,8 +450,6 @@ def _gen_agent_missions( actors=[types.TrafficActor(name="car")], name="missions", output_dir=output_dir, - seed=seed, - overwrite=overwrite, map_spec=map_spec, ) @@ -483,7 +466,6 @@ def _gen_group_laps( vehicle_count: int, num_laps: int = 3, seed: int = 42, - overwrite: bool = False, map_spec: Optional[types.MapSpec] = None, ): """Generates missions that start with a grid offset at the startline and do a number @@ -532,7 +514,6 @@ def _gen_group_laps( scenario=scenario, missions=missions, seed=seed, - overwrite=overwrite, map_spec=map_spec, ) @@ -570,8 +551,6 @@ def _gen_missions( actors: Sequence[types.Actor], name: str, output_dir: str, - seed: int = 42, - overwrite: bool = False, map_spec: Optional[types.MapSpec] = None, ): """Generates a route file to represent missions (a route per mission). Will @@ -598,9 +577,6 @@ def resolve_mission(mission): os.makedirs(output_dir, exist_ok=True) output_path = os.path.join(output_dir, name + ".pkl") - if os.path.exists(output_path) and not overwrite: - return False - _validate_missions(missions) missions = [ @@ -654,7 +630,6 @@ def _validate_entry_tactic(mission): def _gen_traffic_histories( scenario: str, histories_datasets: Sequence[Union[types.TrafficHistoryDataset, str]], - overwrite: bool, map_spec: Optional[types.MapSpec] = None, ): """Converts traffic history to a format that SMARTS can use. @@ -663,8 +638,6 @@ def _gen_traffic_histories( The scenario directory histories_datasets: A sequence of traffic history descriptors. - overwrite: - If to forcefully write over the previous existing output file map_spec: An optional map specification that takes precedence over scenario directory information. """ @@ -690,4 +663,4 @@ def _gen_traffic_histories( f"no map_spec supplied, so unable to filter off-map coordinates and/or flip_y for {hdsr.name}" ) output_dir = os.path.join(scenario, "build") - genhistories.import_dataset(hdsr, output_dir, overwrite, map_bbox) + genhistories.import_dataset(hdsr, output_dir, map_bbox) From 84b6daad5c82d48dda75331ad0d17e62c2d958f9 Mon Sep 17 00:00:00 2001 From: Saul Field Date: Thu, 15 Dec 2022 14:45:17 -0500 Subject: [PATCH 18/19] Removed unused seed params. Made gen_* functions public. --- .../sumo/tests/same_location/scenario.py | 6 +-- smarts/core/tests/test_scenario.py | 6 +-- smarts/sstudio/genscenario.py | 51 ++++++++----------- smarts/sstudio/tests/test_generate.py | 6 +-- zoo/evaluation/scenarios/cross/scenario.py | 4 +- zoo/evaluation/scenarios/cross_1/scenario.py | 6 +-- zoo/evaluation/scenarios/cross_2/scenario.py | 4 +- zoo/evaluation/scenarios/merge/scenario.py | 4 +- zoo/evaluation/scenarios/merge_1/scenario.py | 4 +- zoo/evaluation/scenarios/merge_2/scenario.py | 4 +- .../straight_change-lane_1/scenario.py | 4 +- .../straight_change-lane_2/scenario.py | 4 +- .../scenarios/straight_pick_lane/scenario.py | 4 +- .../scenarios/straight_straight_1/scenario.py | 4 +- .../scenarios/straight_straight_2/scenario.py | 4 +- .../straight_turn-left_1/scenario.py | 4 +- .../straight_turn-left_2/scenario.py | 4 +- .../turn-left_turn-left_1/scenario.py | 4 +- .../turn-left_turn-left_2/scenario.py | 4 +- .../turn-right_turn-left_1/scenario.py | 4 +- .../turn-right_turn-left_2/scenario.py | 4 +- .../scenarios/turnleft_pick_lane/scenario.py | 4 +- 22 files changed, 67 insertions(+), 76 deletions(-) diff --git a/scenarios/sumo/tests/same_location/scenario.py b/scenarios/sumo/tests/same_location/scenario.py index ece7dc6a50..6467d48291 100644 --- a/scenarios/sumo/tests/same_location/scenario.py +++ b/scenarios/sumo/tests/same_location/scenario.py @@ -1,7 +1,7 @@ from pathlib import Path import smarts.sstudio.types as types -from smarts.sstudio.genscenario import _gen_agent_missions, _gen_traffic +from smarts.sstudio.genscenario import gen_agent_missions, gen_traffic scenario = str(Path(__file__).parent) @@ -25,10 +25,10 @@ ] ) -_gen_agent_missions( +gen_agent_missions( scenario, missions=[ types.Mission(shared_route), ], ) -_gen_traffic(scenario, traffic, "traffic") +gen_traffic(scenario, traffic, "traffic") diff --git a/smarts/core/tests/test_scenario.py b/smarts/core/tests/test_scenario.py index 99788b8287..85ae0d52d1 100644 --- a/smarts/core/tests/test_scenario.py +++ b/smarts/core/tests/test_scenario.py @@ -26,7 +26,7 @@ from smarts.core.scenario import Scenario from smarts.core.utils.id import SocialAgentId -from smarts.sstudio.genscenario import _gen_agent_missions, _gen_social_agent_missions +from smarts.sstudio.genscenario import gen_agent_missions, gen_social_agent_missions from smarts.sstudio.types import Mission, Route, SocialAgentActor AGENT_ID = "Agent-007" @@ -57,14 +57,14 @@ def scenario_root(): begin=("edge-north-NS", 1, 0), end=("edge-south-NS", 1, "max") ) missions = [Mission(route=route)] * 2 # double up - _gen_social_agent_missions( + gen_social_agent_missions( scenario_root, social_agent_actor=actors, name=name, missions=missions, ) - _gen_agent_missions( + gen_agent_missions( scenario_root, missions=[ Mission( diff --git a/smarts/sstudio/genscenario.py b/smarts/sstudio/genscenario.py index d35dae40f4..e776171191 100644 --- a/smarts/sstudio/genscenario.py +++ b/smarts/sstudio/genscenario.py @@ -173,7 +173,7 @@ def gen_scenario( obj_hash = pickle_hash(scenario.map_spec, True) if _needs_build(db_conn, scenario.map_spec, artifact_paths, obj_hash): with timeit("map_spec", logger.info): - _gen_map(scenario_dir, scenario.map_spec) + gen_map(scenario_dir, scenario.map_spec) _update_artifacts(db_conn, artifact_paths, obj_hash) map_spec = scenario.map_spec else: @@ -224,7 +224,7 @@ def gen_scenario( ): with timeit("traffic", logger.info): for name, traffic in scenario.traffic.items(): - _gen_traffic( + gen_traffic( scenario=scenario_dir, traffic=traffic, name=name, @@ -243,7 +243,7 @@ def gen_scenario( missions = [] for mission in scenario.ego_missions: if isinstance(mission, types.GroupedLapMission): - _gen_group_laps( + gen_group_laps( scenario=output_dir, begin=mission.route.begin, end=mission.route.end, @@ -251,17 +251,15 @@ def gen_scenario( used_lanes=mission.lanes, vehicle_count=mission.actor_count, num_laps=mission.num_laps, - seed=seed, map_spec=map_spec, ) else: missions.append(mission) if missions: - _gen_agent_missions( + gen_agent_missions( scenario=output_dir, missions=missions, - seed=seed, map_spec=map_spec, ) @@ -285,7 +283,7 @@ def gen_scenario( ): raise ValueError("Actors and missions must be sequences") - _gen_social_agent_missions( + gen_social_agent_missions( name=name, scenario=output_dir, social_agent_actor=actors, @@ -300,7 +298,7 @@ def gen_scenario( obj_hash = pickle_hash(scenario.bubbles, True) if _needs_build(db_conn, scenario.bubbles, artifact_paths, obj_hash): with timeit("bubbles", logger.info): - _gen_bubbles(scenario=output_dir, bubbles=scenario.bubbles) + gen_bubbles(scenario=output_dir, bubbles=scenario.bubbles) _update_artifacts(db_conn, artifact_paths, obj_hash) # Friction maps @@ -308,7 +306,7 @@ def gen_scenario( obj_hash = pickle_hash(scenario.friction_maps, True) if _needs_build(db_conn, scenario.friction_maps, artifact_paths, obj_hash): with timeit("friction_maps", logger.info): - _gen_friction_map( + gen_friction_map( scenario=output_dir, surface_patches=scenario.friction_maps ) _update_artifacts(db_conn, artifact_paths, obj_hash) @@ -320,7 +318,7 @@ def gen_scenario( db_conn, scenario.traffic_histories, artifact_paths, obj_hash, map_needs_rebuild ): with timeit("traffic_histories", logger.info): - _gen_traffic_histories( + gen_traffic_histories( scenario=output_dir, histories_datasets=scenario.traffic_histories, map_spec=map_spec, @@ -328,7 +326,7 @@ def gen_scenario( _update_artifacts(db_conn, artifact_paths, obj_hash) -def _gen_map(scenario: str, map_spec: types.MapSpec, output_dir: Optional[str] = None): +def gen_map(scenario: str, map_spec: types.MapSpec, output_dir: Optional[str] = None): """Saves a map spec to file.""" _check_if_called_externally() build_dir = os.path.join(scenario, "build") @@ -342,7 +340,7 @@ def _gen_map(scenario: str, map_spec: types.MapSpec, output_dir: Optional[str] = cloudpickle.dump(map_spec, f) -def _gen_traffic( +def gen_traffic( scenario: str, traffic: types.Traffic, name: str, @@ -366,7 +364,7 @@ def _gen_traffic( logger.debug(f"Generated traffic for scenario={scenario}") -def _gen_social_agent_missions( +def gen_social_agent_missions( scenario: str, missions: Sequence[types.Mission], social_agent_actor: Union[types.SocialAgentActor, Sequence[types.SocialAgentActor]], @@ -385,8 +383,6 @@ def _gen_social_agent_missions( name: A short name for this grouping of social agents. Is also used as the name of the social agent traffic file - seed: - The random seed to use when generating behavior map_spec: An optional map specification that takes precedence over scenario directory information. """ @@ -400,7 +396,7 @@ def _gen_social_agent_missions( # This doesn't support BoidAgentActor. Here we make that explicit if any(isinstance(actor, types.BoidAgentActor) for actor in actors): raise ValueError( - "_gen_social_agent_missions(...) can't be called with BoidAgentActor, got:" + "gen_social_agent_missions(...) can't be called with BoidAgentActor, got:" f"{actors}" ) @@ -409,7 +405,7 @@ def _gen_social_agent_missions( raise ValueError(f"Actor names={actor_names} must not contain duplicates") output_dir = os.path.join(scenario, "build", "social_agents") - saved = _gen_missions( + saved = gen_missions( scenario=scenario, missions=missions, actors=actors, @@ -422,10 +418,9 @@ def _gen_social_agent_missions( logger.debug(f"Generated social agent missions for scenario={scenario}") -def _gen_agent_missions( +def gen_agent_missions( scenario: str, missions: Sequence, - seed: int = 42, map_spec: Optional[types.MapSpec] = None, ): """Generates a route file to represent missions (a route per mission). Will create @@ -436,15 +431,13 @@ def _gen_agent_missions( The scenario directory missions: A sequence of missions for social agents to perform - seed: - The random seed to use when generating behavior map_spec: An optional map specification that takes precedence over scenario directory information. """ _check_if_called_externally() output_dir = os.path.join(scenario, "build") - saved = _gen_missions( + saved = gen_missions( scenario=scenario, missions=missions, actors=[types.TrafficActor(name="car")], @@ -457,7 +450,7 @@ def _gen_agent_missions( logger.debug(f"Generated missions for scenario={scenario}") -def _gen_group_laps( +def gen_group_laps( scenario: str, begin: Tuple[str, int, Any], end: Tuple[str, int, Any], @@ -465,7 +458,6 @@ def _gen_group_laps( used_lanes: int, vehicle_count: int, num_laps: int = 3, - seed: int = 42, map_spec: Optional[types.MapSpec] = None, ): """Generates missions that start with a grid offset at the startline and do a number @@ -510,10 +502,9 @@ def _gen_group_laps( ) ) - saved = _gen_agent_missions( + saved = gen_agent_missions( scenario=scenario, missions=missions, - seed=seed, map_spec=map_spec, ) @@ -521,7 +512,7 @@ def _gen_group_laps( logger.debug(f"Generated grouped lap missions for scenario={scenario}") -def _gen_bubbles(scenario: str, bubbles: Sequence[types.Bubble]): +def gen_bubbles(scenario: str, bubbles: Sequence[types.Bubble]): """Generates 'bubbles' in the scenario that capture vehicles for actors. Args: scenario: @@ -535,7 +526,7 @@ def _gen_bubbles(scenario: str, bubbles: Sequence[types.Bubble]): pickle.dump(bubbles, f) -def _gen_friction_map(scenario: str, surface_patches: Sequence[types.RoadSurfacePatch]): +def gen_friction_map(scenario: str, surface_patches: Sequence[types.RoadSurfacePatch]): """Generates friction map file according to the surface patches defined in scenario file. """ @@ -545,7 +536,7 @@ def _gen_friction_map(scenario: str, surface_patches: Sequence[types.RoadSurface pickle.dump(surface_patches, f) -def _gen_missions( +def gen_missions( scenario: str, missions: Sequence[types.Mission], actors: Sequence[types.Actor], @@ -627,7 +618,7 @@ def _validate_entry_tactic(mission): ), f"Zone edge `{z_edge}` is not the same edge as `types.Mission` route begin edge `{edge}`" -def _gen_traffic_histories( +def gen_traffic_histories( scenario: str, histories_datasets: Sequence[Union[types.TrafficHistoryDataset, str]], map_spec: Optional[types.MapSpec] = None, diff --git a/smarts/sstudio/tests/test_generate.py b/smarts/sstudio/tests/test_generate.py index 5264ee2549..c49990d7dc 100644 --- a/smarts/sstudio/tests/test_generate.py +++ b/smarts/sstudio/tests/test_generate.py @@ -27,7 +27,7 @@ import pytest from smarts.core.scenario import Scenario -from smarts.sstudio.genscenario import _gen_map, _gen_traffic +from smarts.sstudio.genscenario import gen_map, gen_traffic from smarts.sstudio.types import ( Distribution, Flow, @@ -81,7 +81,7 @@ def missions() -> Sequence[Mission]: def test_generate_traffic(traffic: Traffic): with tempfile.TemporaryDirectory() as temp_dir: - _gen_traffic( + gen_traffic( "scenarios/sumo/intersections/4lane_t", traffic, output_dir=temp_dir, @@ -110,7 +110,7 @@ def _compare_files(file1, file2): def _gen_map_from_spec(scenario_root: str, map_spec: MapSpec): with tempfile.TemporaryDirectory() as temp_dir: - _gen_map(scenario_root, map_spec, output_dir=temp_dir) + gen_map(scenario_root, map_spec, output_dir=temp_dir) found_map_spec = Scenario.discover_map(temp_dir) assert found_map_spec road_map = found_map_spec.builder_fn(found_map_spec) diff --git a/zoo/evaluation/scenarios/cross/scenario.py b/zoo/evaluation/scenarios/cross/scenario.py index 4ca23955dc..978c5167b4 100644 --- a/zoo/evaluation/scenarios/cross/scenario.py +++ b/zoo/evaluation/scenarios/cross/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio.genscenario import _gen_social_agent_missions +from smarts.sstudio.genscenario import gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -_gen_social_agent_missions( +gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/cross_1/scenario.py b/zoo/evaluation/scenarios/cross_1/scenario.py index 40f24df421..002bc98c07 100644 --- a/zoo/evaluation/scenarios/cross_1/scenario.py +++ b/zoo/evaluation/scenarios/cross_1/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio.genscenario import _gen_agent_missions, _gen_social_agent_missions +from smarts.sstudio.genscenario import gen_agent_missions, gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -_gen_social_agent_missions( +gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", @@ -18,7 +18,7 @@ ], ) -_gen_agent_missions( +gen_agent_missions( scenario, [ t.Mission(t.Route(begin=("E3l-3", 1, 200), end=("E3-35", 1, 50))), diff --git a/zoo/evaluation/scenarios/cross_2/scenario.py b/zoo/evaluation/scenarios/cross_2/scenario.py index 4ca23955dc..978c5167b4 100644 --- a/zoo/evaluation/scenarios/cross_2/scenario.py +++ b/zoo/evaluation/scenarios/cross_2/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio.genscenario import _gen_social_agent_missions +from smarts.sstudio.genscenario import gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -_gen_social_agent_missions( +gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/merge/scenario.py b/zoo/evaluation/scenarios/merge/scenario.py index 2432e61c1d..c8103ea370 100644 --- a/zoo/evaluation/scenarios/merge/scenario.py +++ b/zoo/evaluation/scenarios/merge/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio.genscenario import _gen_social_agent_missions +from smarts.sstudio.genscenario import gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -_gen_social_agent_missions( +gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/merge_1/scenario.py b/zoo/evaluation/scenarios/merge_1/scenario.py index ab55eb6fbd..7a9279db88 100644 --- a/zoo/evaluation/scenarios/merge_1/scenario.py +++ b/zoo/evaluation/scenarios/merge_1/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio.genscenario import _gen_social_agent_missions +from smarts.sstudio.genscenario import gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -10,7 +10,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -_gen_social_agent_missions( +gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/merge_2/scenario.py b/zoo/evaluation/scenarios/merge_2/scenario.py index ab55eb6fbd..7a9279db88 100644 --- a/zoo/evaluation/scenarios/merge_2/scenario.py +++ b/zoo/evaluation/scenarios/merge_2/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio.genscenario import _gen_social_agent_missions +from smarts.sstudio.genscenario import gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -10,7 +10,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -_gen_social_agent_missions( +gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/straight_change-lane_1/scenario.py b/zoo/evaluation/scenarios/straight_change-lane_1/scenario.py index f376c8b194..9354c83910 100755 --- a/zoo/evaluation/scenarios/straight_change-lane_1/scenario.py +++ b/zoo/evaluation/scenarios/straight_change-lane_1/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio.genscenario import _gen_social_agent_missions +from smarts.sstudio.genscenario import gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -_gen_social_agent_missions( +gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/straight_change-lane_2/scenario.py b/zoo/evaluation/scenarios/straight_change-lane_2/scenario.py index a8a8a28876..643b76c518 100755 --- a/zoo/evaluation/scenarios/straight_change-lane_2/scenario.py +++ b/zoo/evaluation/scenarios/straight_change-lane_2/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio.genscenario import _gen_social_agent_missions +from smarts.sstudio.genscenario import gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -_gen_social_agent_missions( +gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/straight_pick_lane/scenario.py b/zoo/evaluation/scenarios/straight_pick_lane/scenario.py index ea3579af94..df3b7ab048 100644 --- a/zoo/evaluation/scenarios/straight_pick_lane/scenario.py +++ b/zoo/evaluation/scenarios/straight_pick_lane/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio.genscenario import _gen_social_agent_missions +from smarts.sstudio.genscenario import gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -10,7 +10,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -_gen_social_agent_missions( +gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/straight_straight_1/scenario.py b/zoo/evaluation/scenarios/straight_straight_1/scenario.py index 34dfb78eb5..504f94d63d 100755 --- a/zoo/evaluation/scenarios/straight_straight_1/scenario.py +++ b/zoo/evaluation/scenarios/straight_straight_1/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio.genscenario import _gen_social_agent_missions +from smarts.sstudio.genscenario import gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -_gen_social_agent_missions( +gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/straight_straight_2/scenario.py b/zoo/evaluation/scenarios/straight_straight_2/scenario.py index 9bec8c84b9..9fd94428ba 100755 --- a/zoo/evaluation/scenarios/straight_straight_2/scenario.py +++ b/zoo/evaluation/scenarios/straight_straight_2/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio.genscenario import _gen_social_agent_missions +from smarts.sstudio.genscenario import gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -_gen_social_agent_missions( +gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/straight_turn-left_1/scenario.py b/zoo/evaluation/scenarios/straight_turn-left_1/scenario.py index f5d0fb13c1..585e086f55 100755 --- a/zoo/evaluation/scenarios/straight_turn-left_1/scenario.py +++ b/zoo/evaluation/scenarios/straight_turn-left_1/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio.genscenario import _gen_social_agent_missions +from smarts.sstudio.genscenario import gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -_gen_social_agent_missions( +gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/straight_turn-left_2/scenario.py b/zoo/evaluation/scenarios/straight_turn-left_2/scenario.py index f5d0fb13c1..585e086f55 100755 --- a/zoo/evaluation/scenarios/straight_turn-left_2/scenario.py +++ b/zoo/evaluation/scenarios/straight_turn-left_2/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio.genscenario import _gen_social_agent_missions +from smarts.sstudio.genscenario import gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -_gen_social_agent_missions( +gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/turn-left_turn-left_1/scenario.py b/zoo/evaluation/scenarios/turn-left_turn-left_1/scenario.py index cbbe34c855..80b9a3a7fa 100755 --- a/zoo/evaluation/scenarios/turn-left_turn-left_1/scenario.py +++ b/zoo/evaluation/scenarios/turn-left_turn-left_1/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio.genscenario import _gen_social_agent_missions +from smarts.sstudio.genscenario import gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -_gen_social_agent_missions( +gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/turn-left_turn-left_2/scenario.py b/zoo/evaluation/scenarios/turn-left_turn-left_2/scenario.py index cbbe34c855..80b9a3a7fa 100755 --- a/zoo/evaluation/scenarios/turn-left_turn-left_2/scenario.py +++ b/zoo/evaluation/scenarios/turn-left_turn-left_2/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio.genscenario import _gen_social_agent_missions +from smarts.sstudio.genscenario import gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -_gen_social_agent_missions( +gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/turn-right_turn-left_1/scenario.py b/zoo/evaluation/scenarios/turn-right_turn-left_1/scenario.py index 333b25129c..134309472e 100755 --- a/zoo/evaluation/scenarios/turn-right_turn-left_1/scenario.py +++ b/zoo/evaluation/scenarios/turn-right_turn-left_1/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio.genscenario import _gen_social_agent_missions +from smarts.sstudio.genscenario import gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -_gen_social_agent_missions( +gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/turn-right_turn-left_2/scenario.py b/zoo/evaluation/scenarios/turn-right_turn-left_2/scenario.py index 333b25129c..134309472e 100755 --- a/zoo/evaluation/scenarios/turn-right_turn-left_2/scenario.py +++ b/zoo/evaluation/scenarios/turn-right_turn-left_2/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio.genscenario import _gen_social_agent_missions +from smarts.sstudio.genscenario import gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -_gen_social_agent_missions( +gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", diff --git a/zoo/evaluation/scenarios/turnleft_pick_lane/scenario.py b/zoo/evaluation/scenarios/turnleft_pick_lane/scenario.py index cd092088ec..95654418b1 100644 --- a/zoo/evaluation/scenarios/turnleft_pick_lane/scenario.py +++ b/zoo/evaluation/scenarios/turnleft_pick_lane/scenario.py @@ -1,7 +1,7 @@ import os import pickle -from smarts.sstudio.genscenario import _gen_social_agent_missions +from smarts.sstudio.genscenario import gen_social_agent_missions from smarts.sstudio import types as t scenario = os.path.dirname(os.path.realpath(__file__)) @@ -9,7 +9,7 @@ with open(os.environ["SOCIAL_AGENT_PATH"], "rb") as f: social_agent = pickle.load(f) -_gen_social_agent_missions( +gen_social_agent_missions( scenario, social_agent_actor=social_agent, name=f"s-agent-{social_agent.name}", From 28c8b8bc131bacb18fabcaca41ceaac6df841170 Mon Sep 17 00:00:00 2001 From: Saul Field Date: Fri, 16 Dec 2022 16:01:12 -0500 Subject: [PATCH 19/19] Remove map offset param in build_scenarios, add test for scenario caching --- cli/studio.py | 11 ++--------- cli/tests/test_studio.py | 26 ++++++++++++++++++++++++-- examples/rl/racing/run.py | 1 - smarts/benchmark/run.py | 1 - 4 files changed, 26 insertions(+), 13 deletions(-) diff --git a/cli/studio.py b/cli/studio.py index ac7ce3e57d..62d81a6d44 100644 --- a/cli/studio.py +++ b/cli/studio.py @@ -97,12 +97,6 @@ def _is_scenario_folder_to_build(path: str) -> bool: default=False, help="Clean previously generated artifacts first", ) -@click.option( - "--allow-offset-maps", - is_flag=True, - default=False, - help="Allows road networks (maps) to be offset from the origin. If not specified, a new network file is created if necessary. Defaults to False except when there's Traffic History data associated with the scenario.", -) @click.option( "--seed", type=int, @@ -110,13 +104,12 @@ def _is_scenario_folder_to_build(path: str) -> bool: help="Set the base seed of the scenarios.", ) @click.argument("scenarios", nargs=-1, metavar="") -def build_all(clean: bool, allow_offset_maps: bool, scenarios: List[str], seed: int): - build_scenarios(clean, allow_offset_maps, scenarios, seed) +def build_all(clean: bool, scenarios: List[str], seed: int): + build_scenarios(clean, scenarios, seed) def build_scenarios( clean: bool, - allow_offset_maps: bool, scenarios: List[str], seed: Optional[int] = None, ): diff --git a/cli/tests/test_studio.py b/cli/tests/test_studio.py index a146237199..bb82f717e1 100644 --- a/cli/tests/test_studio.py +++ b/cli/tests/test_studio.py @@ -22,6 +22,7 @@ import os import shutil import tempfile +import time from xml.etree.ElementTree import ElementTree @@ -53,10 +54,10 @@ def test_scenario_generation_unchanged(): assert _hashseed not in (None, "random"), f"PYTHONHASHSEED is {_hashseed}" shutil.copytree("scenarios/sumo", loc1) - build_scenarios(True, True, [loc1], 42) + build_scenarios(True, [loc1], 42) shutil.copytree("scenarios/sumo", loc2) - build_scenarios(True, True, [loc2], 42) + build_scenarios(True, [loc2], 42) for dirpath, dirnames, files in os.walk(loc1): if "traffic" in dirpath: @@ -67,3 +68,24 @@ def test_scenario_generation_unchanged(): number_of_comparisons_greater_than_0 = True assert number_of_comparisons_greater_than_0 + + +def test_scenario_build_caching(): + from cli.studio import build_scenarios + + with tempfile.TemporaryDirectory() as temp_dir1: + scenario_dir = temp_dir1 + "/scenario" + shutil.copytree("scenarios/sumo/loop", scenario_dir) + + # Clean & build the scenario + start = time.time() + build_scenarios(True, [scenario_dir]) + elapsed1 = time.time() - start + + # Build again without cleaning + start = time.time() + build_scenarios(False, [scenario_dir]) + elapsed2 = time.time() - start + + # Second build should be much faster because of caching + assert 2 * elapsed2 < elapsed1 diff --git a/examples/rl/racing/run.py b/examples/rl/racing/run.py index 312f93927e..a0c2d43aa9 100644 --- a/examples/rl/racing/run.py +++ b/examples/rl/racing/run.py @@ -53,7 +53,6 @@ def main(args: argparse.Namespace): # Build the scenarios. _build_all_scenarios( clean=True, - allow_offset_maps=False, scenarios=[config_env["scenarios_dir"]], seed=_SEED, ) diff --git a/smarts/benchmark/run.py b/smarts/benchmark/run.py index 71045362a9..e4f8e2da0a 100644 --- a/smarts/benchmark/run.py +++ b/smarts/benchmark/run.py @@ -49,7 +49,6 @@ def _compute(scenario_dir, ep_per_scenario=10, max_episode_steps=_MAX_EPISODE_STEPS): build_scenarios( - allow_offset_maps=False, clean=False, scenarios=scenario_dir, seed=_SEED,