From 3f3adecf65fc500a0963d0fed80183f168083050 Mon Sep 17 00:00:00 2001 From: eugenevinitsky Date: Thu, 9 Aug 2018 15:29:07 -0700 Subject: [PATCH 01/25] no backoff in unit tests --- flow/envs/base_env.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/flow/envs/base_env.py b/flow/envs/base_env.py index f24fe1fcb..1cc1c4db7 100755 --- a/flow/envs/base_env.py +++ b/flow/envs/base_env.py @@ -72,7 +72,8 @@ def __init__(self, env_params, sumo_params, scenario): self.scenario = scenario self.sumo_params = sumo_params time_stamp = ''.join(str(time.time()).split('.')) - time.sleep(8.0 * int(time_stamp[-6:]) / 1e6) + if os.environ.get("TEST_FLAG", 0): + time.sleep(8.0 * int(time_stamp[-6:]) / 1e6) self.sumo_params.port = sumolib.miscutils.getFreeSocketPort() self.vehicles = scenario.vehicles self.traffic_lights = scenario.traffic_lights From ca6fe568d5e55e63a08f77d089736c066e1f06c9 Mon Sep 17 00:00:00 2001 From: eugenevinitsky Date: Thu, 9 Aug 2018 16:00:25 -0700 Subject: [PATCH 02/25] fixed sumo build instructions for linux --- docs/source/flow_setup.rst | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/docs/source/flow_setup.rst b/docs/source/flow_setup.rst index 909106f85..823078ba4 100644 --- a/docs/source/flow_setup.rst +++ b/docs/source/flow_setup.rst @@ -45,8 +45,14 @@ human-driven agents during the simulation process. cd sumo git checkout 1d4338ab80 make -f Makefile.cvs + +If you have OSX, run the following commands +:: export CPPFLAGS=-I/opt/X11/include export LDFLAGS=-L/opt/X11/lib + +Now for both OSX and linux run the following command +:: ./configure make -j$nproc echo 'export SUMO_HOME="$HOME/sumo"' >> ~/.bashrc @@ -54,6 +60,12 @@ human-driven agents during the simulation process. echo 'export PYTHONPATH="$HOME/sumo/tools:$PYTHONPATH"' >> ~/.bashrc source ~/.bashrc +Test your sumo install and version by running the following commands +:: + which sumo + sumo --version + sumo-gui + Flow ==== Once sumo and the various dependencies are in place, we are ready to install a From 63c12f5bea2cd1baa7b41f21bbc288579c8c4c5b Mon Sep 17 00:00:00 2001 From: AboudyKreidieh Date: Thu, 9 Aug 2018 17:24:55 -0700 Subject: [PATCH 03/25] moved changes from flow-devel --- README.md | 2 +- docs/source/tutorial.rst | 1069 ----------------- examples/__init__.py | 0 examples/rllib/test_rllib.py | 133 -- examples/sumo/bay_bridge.py | 149 +++ examples/sumo/bay_bridge_toll.py | 107 ++ flow/controllers/car_following_models.py | 4 - flow/core/experiment.py | 13 +- flow/envs/__init__.py | 10 +- flow/envs/bay_bridge/__init__.py | 3 + flow/envs/bay_bridge/base.py | 211 ++++ flow/envs/test.py | 45 + flow/scenarios/__init__.py | 14 +- flow/scenarios/bay_bridge/gen.py | 77 ++ flow/scenarios/bay_bridge/scenario.py | 31 + flow/scenarios/bay_bridge_toll/gen.py | 49 + flow/scenarios/bay_bridge_toll/scenario.py | 27 + scripts/ray_autoscale.yaml | 20 +- tests/fast_tests/test_controllers.py | 3 +- .../fast_tests/test_experiment_base_class.py | 34 + 20 files changed, 770 insertions(+), 1231 deletions(-) delete mode 100644 docs/source/tutorial.rst create mode 100644 examples/__init__.py delete mode 100644 examples/rllib/test_rllib.py create mode 100644 examples/sumo/bay_bridge.py create mode 100644 examples/sumo/bay_bridge_toll.py create mode 100644 flow/envs/bay_bridge/__init__.py create mode 100644 flow/envs/bay_bridge/base.py create mode 100644 flow/envs/test.py create mode 100644 flow/scenarios/bay_bridge/gen.py create mode 100644 flow/scenarios/bay_bridge/scenario.py create mode 100644 flow/scenarios/bay_bridge_toll/gen.py create mode 100644 flow/scenarios/bay_bridge_toll/scenario.py diff --git a/README.md b/README.md index 25109cf2a..9851c4522 100644 --- a/README.md +++ b/README.md @@ -12,7 +12,7 @@ See [our website](https://berkeleyflow.github.io) for more information on the ap - [Documentation](https://berkeleyflow.readthedocs.org/en/latest/) - [Installation instructions](http://berkeleyflow.readthedocs.io/en/latest/flow_setup.html) -- [Tutorial](http://berkeleyflow.readthedocs.io/en/latest/tutorial.html) +- [Tutorials](https://github.com/berkeleyflow/flow/tree/master/tutorials) # Getting involved diff --git a/docs/source/tutorial.rst b/docs/source/tutorial.rst deleted file mode 100644 index 6b2b8544a..000000000 --- a/docs/source/tutorial.rst +++ /dev/null @@ -1,1069 +0,0 @@ -Tutorial -****************** - -1. Introduction -=============== - -This tutorial is intended for readers who are new to Flow. While some -reinforcement learning terms are presented within the contents of this tutorial, -no prior background in the field is required to successfully complete any -steps. Be sure to install Flow before starting this tutorial. - -1.1. About Flow ------------------ - -Flow is a framework for deep reinforcement learning in -mixed-autonomy traffic scenarios. It interfaces the RL library ``rllab`` -with the traffic microsimulator ``SUMO``. Through Flow, autonomous -vehicles may be trained to perform various tasks that improve the -performance of traffic networks. Currently, Flow v0.1 supports the -implementation of simple closed networks, such as ring roads, figure -eights, etc... In order to run an experiment on Flow, three objects are -required: - -- A **Generator**: Generates the configuration files needed to create - a transportation network with ``SUMO``. -- A **Scenario**: Specifies the location of edge nodes in the network, - as well as the positioning of vehicles at the start of a run. -- An **Environment**: ties the components of ``SUMO`` and ``rllab`` together, - running a system of vehicles in a network over discrete time steps, - while treating some of these vehicles as reinforcement learning - agents whose actions are specified by ``rllab``. - -Once the above classes are ready, an **experiment** may be prepared to -run the environment for various levels of autonomous vehicle penetration -ranging from 0% to 100%. - - -1.2. About this tutorial ------------------------- - -In this tutorial, we will create a simple ring road network, which in the -absence of autonomous vehicles, experience a phenomena known as "stop-and-go -waves". An autonomous vehicle in then included into the network and trained -to attenuate these waves. The remainder of the tutorial is organized as follows: - -- In Sections 2, 3, and 4, we create the primary classes needed to run - a ring road experiment. -- In Section 5, we run an experiment in the absence of autonomous - vehicles, and witness the performance of the network. -- In Section 6, we run the experiment with the inclusion of autonomous - vehicles, and discuss the changes that take place once the - reinforcement learning algorithm has converged. - - -.. _creating-a-generator: - -2 Creating a Generator -====================== - -This section walks you through the steps needed to create a generator class. -The generator prepares the configuration files needed to create a -transportation network in sumo. A transportation network can be thought -of as a directed graph consisting of nodes, edges, routes, and other -(optional) elements. - -.. _inheriting-the-base-generator: - -2.1 Inheriting the Base Generator ---------------------------------- - -We begin by creating a file called ``my_generator.py``. In this file, we -create a class titled ``myGenerator`` that inherits the properties of Flow's -base generator class. - -:: - - # import Flow's base generator - from flow.core.generator import Generator - - # some mathematical operations that may be used - from numpy import pi, sin, cos, linspace - - # define the generator class, and inherit properties from the base generator - class myGenerator(Generator): - -The base generator class accepts a single input: - -* **net\_params**: contains network parameters specified during task - initialization. Unlike most other parameters, net\_params may vary drastically - dependent on the specific network configuration. For the ring road, the - network parameters will include a characteristic radius, number of lanes, - and speed limit. - -Once the base generator has been inherited, creating a child class -becomes very systematic. All child classes are required to define at -least the following three function: ``specify_nodes``, -``specify_edges``, and ``specify_routes``. In addition, the following -optional functions also may be specified: ``specify_types``, -``specify_connections``, ``specify_rerouters``. All of the functions -mentioned in the above paragraph take in as input net\_params, and -output a list of dictionary elements, with each element providing the -attributes of the component to be specified. - -.. _defining-the-location-of-nodes: - -2.2 Defining the Location of Nodes ----------------------------------- - -The nodes of a network are the positions of a select few points in the -network. These points are connected together using edges (see `section -2.3`_). For the ring network, we place four nodes at the bottom, right, left, -and right of the ring. - -.. _section 2.3: defining-the-properties-of-edges_ - -In order to specify the location of the nodes that will be placed in the -network, the function ``specify_nodes`` is used. This function provides the -base class with a list of dictionary elements, with the elements containing -attributes of the nodes. These attributes must include: - -- **id**: name of the node -- **x**: x coordinate of the node -- **y**: y coordinate of the node - -Other possible attributes may be found at: -http://sumo.dlr.de/wiki/Networks/Building_Networks_from_own_XML-descriptions#Node_Descriptions - -In order to properly specify the nodes, add the following method to the -generator class: - -:: - - def specify_nodes(self, net_params): - # one of the elements net_params will need is a "radius" value - r = net_params.additional_params["radius"] - - # specify the name and position (x,y) of each node - nodes = [{"id": "bottom", "x": repr(0), "y": repr(-r)}, - {"id": "right", "x": repr(r), "y": repr(0)}, - {"id": "top", "x": repr(0), "y": repr(r)}, - {"id": "left", "x": repr(-r), "y": repr(0)}] - - return nodes - -.. _defining-the-properties-of-edges: - -2.3 Defining the Properties of Edges ------------------------------------- - -Once the nodes are specified, the nodes are linked together using directed -edges. The attributes of these edges are defined in the ``specify_edges`` -function, and must include: - -- **id**: name of the edge -- **from**: name of the node the edge starts from -- **to**: the name of the node the edges ends at -- **length**: length of the edge -- **numLanes**: the number of lanes on the edge -- **speed**: the speed limit for vehicles on the edge - -Other possible attributes can be found at: -http://sumo.dlr.de/wiki/Networks/Building_Networks_from_own_XML-descriptions#Edge_Descriptions. - -One useful attribute is **shape**, which specifies the shape of the edge -connecting the two nodes. The shape consists of a series of subnodes -(internal to sumo) that are connected together by straight lines to -create a shape. If no shape is specified, the nodes are connected by a -straight line. This attribute will be needed to create the circular arcs -between the nodes in the system. In order to properly specify the edges -of the ring road, add the follow function to the generator class: - -:: - - def specify_edges(self, net_params): - r = net_params.additional_params["radius"] - edgelen = r * pi / 2 - # this will let us control the number of lanes in the network - lanes = net_params.additional_params["lanes"] - # speed limit of vehicles in the network - speed_limit = net_params.additional_params["speed_limit"] - - edges = [{"id": "bottom", "numLanes": repr(lanes), "speed": repr(speed_limit), - "from": "bottom", "to": "right", "length": repr(edgelen), - "shape": " ".join(["%.2f,%.2f" % (r * cos(t), r * sin(t)) - for t in linspace(-pi / 2, 0, 40)])}, - {"id": "right", "numLanes": repr(lanes), "speed": repr(speed_limit), - "from": "right", "to": "top", "length": repr(edgelen), - "shape": " ".join(["%.2f,%.2f" % (r * cos(t), r * sin(t)) - for t in linspace(0, pi / 2, 40)])}, - {"id": "top", "numLanes": repr(lanes), "speed": repr(speed_limit), - "from": "top", "to": "left", "length": repr(edgelen), - "shape": " ".join(["%.2f,%.2f" % (r * cos(t), r * sin(t)) - for t in linspace(pi / 2, pi, 40)])}, - {"id": "left", "numLanes": repr(lanes), "speed": repr(speed_limit), - "from": "left", "to": "bottom", "length": repr(edgelen), - "shape": " ".join(["%.2f,%.2f" % (r * cos(t), r * sin(t)) - for t in linspace(pi, 3 * pi / 2, 40)])}] - - return edges - -2.4 Defining Routes Vehicles can Take -------------------------------------- - -The routes are the sequence of edges vehicles traverse given their -current position. For example, a vehicle beginning in the edge titled "bottom" -(see section 2.3) must traverse, in sequence, the edges "bottom", "right", top", -and "left", before restarting its path. - -In order to specify the routes a vehicle may take, the function -``specify_routes`` is used. This function outputs a single dict element, in which -the keys are the names of all starting edges, and the items are the sequence of -edges the vehicle must follow starting from the current edge. For this network, -the available routes are defined as follows: - -:: - - def specify_routes(self, net_params): - rts = {"top": ["top", "left", "bottom", "right"], - "left": ["left", "bottom", "right", "top"], - "bottom": ["bottom", "right", "top", "left"], - "right": ["right", "top", "left", "bottom"]} - - return rts - -.. _creating-a-scenario: - -3 Creating a Scenario -===================== - -This section walks you through the steps required to create a scenario class. -This class is used to generate starting positions for vehicles in the -network, as well as specify the location of edges relative to some reference. - -.. _inheriting-the-base-scenario-class: - -3.1 Inheriting the Base Scenario Class --------------------------------------- - -Similar to the generator we created in section 2, we begin by inheriting the -methods from Flow's base scenario class. Create a new script called -``my_scenario.py`` and begin the script as follows: - -:: - - # import Flow's base scenario class - from flow.scenarios.base_scenario import Scenario - - # import some math functions we may use - from numpy import pi - - # define the scenario class, and inherit properties from the base scenario class - class myScenario(Scenario): - - -The inputs to Flow's base scenario class are: - -- **name**: the name assigned to the scenario -- **generator\_class**: the generator class we created - in `section 2`_ -- **vehicles**: used to initialize a set of vehicles in the network. - In addition, this object contains information on the state of the vehicles - in the network for each time step, which can be accessed during an experiment - through various "get" functions -- **net\_params**: see `section 2.1`_ -- **initial\_config**: affects the positioning of vehicle in the network at - the start of a rollout. By default, vehicles are uniformly distributed in - the network. - -.. _section 2.1: inheriting-the-base-generator_ - -.. _section 3.2: - -3.2 Specifying the Length of the Network (optional) ---------------------------------------------------- - -The base scenario class will look for a "length" parameter in -net\_params upon initialization. However, this value is implicitly -defined by the radius of the ring, making specifying the length a -redundancy. In order to avoid any confusion when creating net_params -during an experiment run (see sections 5 and 6), the length of the -network can be added to net_params via our scenario subclass's -initializer. This is done by defining the initializer as follows: - -:: - - def __init__(self, name, generator_class, vehicles, net_params, - initial_config=None): - # add to net_params a characteristic length - net_params.additional_params["length"] = 2 * pi * net_params.additional_params["radius"] - -Then, the initializer is finished off by setting the number of lanes -and adding the base (super) class's initializer: - -:: - - self.lanes = net_params.additional_params["lanes"] - super().__init__(name, generator_class, vehicles, net_params, initial_config) - -3.3 Specifying the Starting Position of Edges ---------------------------------------------- - -The starting position of the edges are the only adjustments to the -scenario class that *need* to be performed in order to have a fully -functional subclass. These values specify the distance the edges within -the network are from some reference, in one dimension. To this end, up -to three functions may need to be overloaded within the subclass: - -- ``specify_edge_starts``: defines edge starts for road sections with respect - to some global reference -- ``specify_intersection_edge_starts`` (optional): defines edge starts for - intersections with respect to some global reference frame. Only needed by - environments with intersections. -- ``specify_internal_edge_starts``: defines the edge starts for internal edge - nodes caused by finite length connections between road section - -All of the above functions receive no inputs and output a list -of tuples, in which the first element of the tuple is the name of the -edge/intersection/internal\_link, and the second value is the distance -of the link from some global reference, i.e. -``[(link_0, pos_0, link_1, pos_1, ...]``. - -In section 2, we created a network with 4 edges named: "bottom", "right", -"top", and "left". We assume that the node titled "bottom" is the origin, and -accordingly the position of the edge start of edge "bottom" is ``0``. The edge -begins a quarter of the length of the network from the node "bottom", and -accordingly the position of its edge start is ``radius * pi/2``. This process -continues for each of the edges. We can then define the starting position of the -edges as follows: - -:: - - def specify_edge_starts(self): - r = self.net_params.additional_params["radius"] - - edgestarts = [("bottom", 0), - ("right", r * 1/2 *pi), - ("top", r * pi), - ("left", r * 3/2 * pi)] - - return edgestarts - -Our road network does not contain intersections, and internal links are -not used in this experiment and outside the scope of the problem. -Accordingly, the methods ``specify_intersection_edge_starts`` and -``specify_internal_edge_starts`` are not used in this example. - -3.4 Controlling the Starting Positions of Vehicles --------------------------------------------------- - -Flow v0.1 supports the use of several positioning methods for closed -network systems. These methods include: - -- a **uniform** distribution, in which all vehicles are placed - uniformly spaced across the length of the network -- a **gaussian** distribution, in which the vehicles are perturbed from - their uniform starting position following a gaussian distribution -- a **gaussian-additive** distribution, in which vehicle are placed - sequentially following a gaussian distribution, thereby causing the - error to build up - -In addition to the above distributions, the user may specify a custom set of -starting position by overriding the function ``gen_custom_start_pos``. This is -not part of the scope of this tutorial, and will not be covered. - -4 Creating an Environment -========================= - -This section walks you through creating an environment class. -This class is the most significant component once a -network is generated. This object ties the components of ``SUMO`` and -``rllab`` together, running a system of vehicles in a network for -discrete time steps, while treating some of these vehicles as -reinforcement learning agents whose actions are specified by ``rllab``. - -4.1 Inheriting the Base Environment Class ------------------------------------------ - -For the third and final time, we will begin by inheriting a core base -class from Flow. Create a new script called ``my_environment.py``, and begin -by importing Flow's base environment class. - -:: - - # import the base environment class - from flow.envs.base_env import SumoEnvironment - -In addition to Flow's base environment, we will import numpy and a few objects -from ``gym``, which will make our environment class compatible with ``rllab``'s -base Environment class. - -The first method we will need is ``Box``, which is used to define a bounded -array of values in :math:`\mathbb{R}^n`. - -:: - - from gym.spaces.box import Box - -In addition, we will import ``Tuple``, which allows us to combine -multiple ``Box`` elements together. - -:: - - from gym.spaces.tuple_space import Tuple - - import numpy as np - -Now, create your environment class titled ``myEnvironment`` with the -base environment class as its parent. - -:: - - # define the environment class, and inherit properties from the base environment class - class myEnvironment(SumoEnvironment): - -Flow's base environment class contains the bulk of the SUMO-related operations -needed, such as specifying actions to be performed by vehicles and collecting -information on the network/vehicles for any given time step. In addition, the -base environment accepts states, actions, and rewards for the new step, and -outputs them to the reinforcement learning algorithm in ``rllab``, which in turn -trains the reinforcement learning agent(s) (i.e. the autonomous vehicles). - -The inputs to the environment class are: - -- **env\_params**: provides several environment and experiment-specific - parameters. This includes specifying the parameters of the action space - and relevant coefficients to the reward function. -- **sumo\_params**: used to pass the time step and sumo-specified safety - modes, which constrain the dynamics of vehicles in the network to - prevent crashes. In addition, this parameter may be used to specify whether to - use sumo's gui during the experiment's runtime. -- **scenario**: The scenario class we created in `section 3`_ - -.. _section 3: creating-a-scenario_ - -By inheriting Flow's base environment, a custom environment can be created -by adding the following functions to the child class: ``action_space``, -``observation_space``, ``apply_rl_action``, ``get_state``, and -``compute_reward``, which are covered in the next few subsections. - -4.2 Specifying an Action Space ------------------------------- - -The components of the action space are in the function conveniently -called ``action_space``; accordingly, we begin by defining this -function: - -:: - - @property - def action_space(self): - -The action space of an environment informs ``rllab`` on the number of -actions a given reinforcement learning agent can perform and the bounds on those -actions. In our single-lane ring road setting, autonomous vehicles can only -accelerate and decelerate, with each vehicle requiring a separate acceleration. -Moreover, their accelerations are bounded by maximum and minimum values -specified by the user. - -Accordingly, we specify the number actions performed by the rl agent and bounds -of these actions as follows: - -:: - - num_acc_actions = self.vehicles.num_rl_vehicles - acc_upper_bound = self.env_params.additional_params["max-acc"] - acc_lower_bound = - abs(self.env_params.additional_params["max-deacc"]) - -Once the parameters of the action space are specified, the ``Box`` element -containing these attributes is defined as follows: - -:: - - acc_action_space = Box(low=acc_lower_bound, high=acc_upper_bound, shape=num_acc_actions) - - return acc_action_space - -4.3 Specifying an Observation Space ------------------------------------ - -The observation space of an environment represents the number and types -of observations that are provided to the reinforcement learning agent. -Assuming the system of vehicles are **fully** observable, -the observation space then consists of a vector of velocities :math:`v` and -absolute positions :math:`x` for each vehicle in the network. - -We begin by defining our ``observation_space`` function: - -:: - - @property - def observation_space(self): - -In this function, we create two Box elements; one for the absolute -positions of the vehicles, and another for the speeds of the vehicles. -These values may range from zero to infinity, and there is a separate value -for each vehicles: - -:: - - speed = Box(low=0, high=np.inf, shape=(self.vehicles.num_vehicles,)) - absolute_pos = Box(low=0., high=np.inf, shape=(self.vehicles.num_vehicles,)) - -Finally, we combine the two ``Box`` elements using the Tuple method. -This tuple used at the output from the ``observation_space`` function: - -:: - - return Tuple([speed, absolute_pos]) - -4.4 Applying Actions to the Autonomous Vehicles ------------------------------------------------ - -The function ``apply_rl_action`` acts as the bridge between ``rllab`` and -``sumo``, transforming commands specified by ``rllab`` in the action space into -actual action in the traffic scenario created within ``sumo``. This function -takes as an input the actions requested by ``rllab``, and sends the commands -to SUMO without returning any output. We begin by defining it: - -:: - - def apply_rl_actions(self, rl_actions): - -Taking into consideration the action space specified in section 4.2, the -array of rl actions provided to ``apply_rl_action`` consists solely of -the accelerations the autonomous vehicles need to perform. These values -may be turned into accelerations in SUMO using the function -``apply_acceleration`` , which takes as inputs a list of vehicle -identifiers and acceleration values, and sends the proper commands to -SUMO. Using this function, the method needed to apply rl actions is -simply as follows: - -:: - - rl_ids = self.rl_ids # the variable self.rl_ids contains a list of the names of all rl vehicles - self.apply_acceleration(rl_ids, rl_actions) - -4.5 Collecting the State Space Information ------------------------------------------- - -As mentioned in section 4.3, the observation space consists of the speed -and position of all vehicles in the network. In order to supply the rl -algorithm with these values, the function ``get_state`` is used. This -function returns a matrix containing the components of the observation -space to the base environment. - -In order to collect the states of specific vehicles in the network for -the current time step, the variable ``self.vehicles`` can be used. This object -stores all sorts of information of the states of vehicles in the network, such -as their speed, edge, position, etc... This information can be accessed from -different "get" functions. - -In order to create the necessary matrix of states, the function get\_state -loops through the vehicle ids of all vehicles in the network, and collects for -each vehicle its speed and absolute position: - -:: - def get_state(self, **kwargs): - state = np.array([[self.vehicles.get_speed(veh_id), - self.vehicles.get_absolute_position(veh_id)] - for veh_id in self.ids]) - return state - -.. _section 4.6: - -4.6 Computing an Appropriate Reward Function --------------------------------------------- - -The reward function is the component which the reinforcement learning -algorithm will attempt to maximum over. This is defined in the function -``compute_reward``: - -:: - - def compute_reward(self, state, rl_actions, **kwargs): - -We choose a simple reward function to encourage high system-level -velocity. This function measures the deviation of a system of vehicles -from a user-specified desired velocity, peaking when all vehicles in the -ring are set to this desired velocity. Moreover, in order to ensure that -the reward function naturally punishing the early termination of -rollouts due to collisions or other failures, the function is formulated -as a mapping: :math:`r : S\times A \to R \geq 0`. This is done by subtracting -the deviation of the system from the desired velocity from the peak allowable -deviation from the desired velocity. Additionally, since the velocity of -vehicles are unbounded above, the reward is bounded below by zero, to ensure -nonnegativity. - -Define :math:`v_{des}` as the desired velocity, :math:`1^k` a vector of ones of -length :math:`k`, :math:`n` as the number of vehicles in the system, and -:math:`v` as a vector of velocities. The reward function is formulated as: - -.. math:: r(v) = \max{0, ||v_{des} \cdot 1^k ||_2 - || v - v_{des} \cdot 1^k ||_2} - -**4.6.1 Using Built-in Reward Functions** Flow comes with several -built-in reward functions located in ``flow.core.rewards``. -In order to use these reward function, we begin by importing these reward -function at the top of the script: - -:: - - # Flow's built-in reward functions - from flow.core import rewards - -One reward function located in the ``rewards`` file is the function -``desired_velocity``, which computes the reward described in this -section. It takes as input the environment variable (``self``) and a -"fail" variables that specifies if the vehicles in the network -experiences any sort of crash, and is an element of the ``**kwargs`` -variable. Returning to the ``compute_reward`` function, the reward may -be specified as follows: - -:: - - return rewards.desired_velocity(self, fail=kwargs["fail"]) - -**4.6.2 Building the Reward Function** In addition to using Flow's -built-in reward functions, you may also choose to create your own -functions from scratch. In doing so, you may choose to use as inputs the -state, actions, or environment (self) variables, as they are presented -in the current time step. In addition, you may use any available -``**kwargs`` variables. In the most general setting, ``kwargs`` will -come with a "fail" element, which describes whether a crash or some -other failure has occurred within the network. In order to prevent the -reward function from outputting a reward when a fail has occurred, we -begin by setting all rewards to zero when "fail" is true: - -:: - - if kwargs["fail"]: - return 0 - -Next, we collect the cost of deviating from the desired velocity. This -is done by taking the two-norm of the difference between the current -velocities of vehicles and their desired velocities. - -:: - - vel = np.array(self.vehicles.get_speed(self.ids)) - - cost = vel - self.env_params.additional_params["target_velocity"] - cost = np.linalg.norm(cost) - -Finally, in order to ensure the value remains positive, we subtract this -deviation from the maximum allowable deviation, and clip the value from -below by zero. - -:: - - max_cost = np.array([self.env_params.additional_params["target_velocity"]] * self.vehicles.num_vehicles) - max_cost = np.linalg.norm(max_cost) - - return max(max_cost - cost, 0) - -4.7 Registering the Environment as a Gym Environment ----------------------------------------------------- - -In order to run reinforcement learning experiments (see section 6), the -environment we created needs to be registered as a Gym Environment. In -order for Flow to register your environment as a Gym Environment, go -to ``flow/envs/__init__.py``, and add the following line: - -:: - - from .my_environment import myEnvironment - -5. Running an Experiment without Autonomy -========================================= - -Once the classes described in sections 2, 3, and 4 are created, we are -now ready to run experiments with Flow. We begin by running an -experiment without any learning/autonomous agents. This experiment acts -as our control case, and helps us ensure that the system exhibits the -sorts of performance deficiencies we expect to witness. In the case of a -single-lane ring road, this deficiency is the phenomenon known as string -instability, in which vehicles begin producing stop-and-go waves among -themselves. - -5.1 Importing the Necessary Modules ------------------------------------ - -In order to run the experiment in the absence of autonomy, we will -create a ``SumoExperiment`` object. This variable takes as input the -environment and scenario classes developed in sections 3 and 4. Note -that the generator class is not needed by the experiment class, but -rather by the scenario class. - -We begin by creating a new script in the same directory as that of the -generator and scenario classes titled ``my_control_experiment.py``. In -this script, we import the base experiment class, as well as the -generator, scenario, and environment subclasses we developed. - -:: - - # this is the base experiment class - from flow.core.experiment import SumoExperiment - - # these are the classes I created - from my_generator import myGenerator - from my_scenario import myScenario - from my_environment import myEnvironment - - # for possible mathematical operations we may want to perform - import numpy as np - -In order to specify the inputs needed for each class, a few objects are also -imported from Flow. - -:: - - # input objects to my classes - from flow.core.params import SumoParams, EnvParams, InitialConfig, NetParams - from flow.core.vehicles import Vehicles - -Finally, in order to impose realistic vehicle dynamics on the vehicles in the -network, Flow possesses a few acceleration, lane-changing, and routing -controller classes. These classes are imported into the script as -follows: - -:: - - from flow.controllers.car_following_models import * - from flow.controllers.lane_change_controllers import * - from flow.controllers.routing_controllers import * - -5.2 Setting Up the Environment and Scenario Classes ---------------------------------------------------- - -In order to initialize scenario and environment classes (as well as the -generator class which is initialized within the scenario), the inputs -for each class, must be must be specified. These inputs are: -``sumo_params``, ``vehicles``, ``env_params``, ``net_params``, and (optionally) -``initial_config``. - -For the ``sumo_params`` input, we specify a time step of 0.1 s and turn on -sumo's gui to visualize the experiment as it happens: - -:: - - sumo_params = SumoParams(time_step=0.1, sumo_binary="sumo-gui") - -Next, we initialize an empty vehicles object: - -:: - - vehicles = Vehicles() - -22 human-driven vehicles are introduced to the vehicles object. These vehicles -are made to follow car-following dynamics defined by the Intelligent Driver -Model (IDM), and are rerouted every time they reach the end of their route -in order to ensure they stay in the ring indefinitely. This is done as follows: - -:: - - vehicles.add_vehicles(veh_id="idm", - acceleration_controller=(IDMController, {}), - routing_controller=(ContinuousRouter, {}), - num_vehicles=22) - -For the ``env_params`` object, we specify the bounds of the action space. -We do this because ``rllab`` will continue to try to create an action space -object despite whether the outputted actions are used (such as in this base -experiment). These terms are added to the "additional_params" portion: - -:: - - additional_env_params = {"max-deacc": 3, "max-acc": 3} - env_params = EnvParams(additional_params=additional_env_params) - - -In the ``net_params`` object, we add the characteristic components of the -network. These values include: "radius", "lanes", -and "speed\_limit", and are added to the "additional_params" portion of the -network we descibed in `section 2`_. - -.. _section 2: creating-a-generator_ - -:: - - additional_net_params = {"radius": 230 / (2*np.pi), "lanes": 1, "speed_limit": 30} - net_params = NetParams(additional_params=additional_net_params) - - -Note that, if `section 3.2`_ was not implemented when creating the scenario -class, an additional "length" component must be added to ``net_params`` -as follows: - -:: - - net_params.additional_params["length"] = net_params.additional_params["radius"] * 2 * np.pi - -Finally, in order to prevent the system from being perfectly symmetric, we add -a bunching component to the initial positioning of the vehicles, which is by -default "uniform": - -:: - - initial_config = InitialConfig(bunching=20) - - -Once all the necessary inputs are prepared, the scenario and environment -variables can be initialized. Moreover, naming the experiment -"ring\_road\_all\_human", the classes are created as followed: - -:: - - # create a scenario object - scenario = myScenario("ring_road_all_human", myGenerator, vehicles, net_params, - initial_config) - - # create an environment object - env = myEnvironment(env_params, sumo_params, scenario) - -5.3 Setting up the Experiment Class ------------------------------------ - -Once the environment and scenario classes are ready, the experiment -variable can be creating as follows: - -:: - - # creating an experiment object - exp = SumoExperiment(env, scenario) - -This allows us to run the experiment for as many runs and any number of -time steps we would like. In order to run the experiment for 1 run of -150 seconds, we specify the following values: - -:: - - num_runs = 1 # I would like to run the experiment once - num_steps = 150 / sumo_params.time_step # I would like the experiment to run for 150 sec - -Finally, we get the script to run the experiment by adding the following -line: - -:: - - exp.run(num_runs, num_steps) - -5.4 Running the Experiment --------------------------- - -Now that all the necessay classes are ready and the experiment script is -prepared, we can finally run our first experiment. Run the script titled -``my_control_experiment.py`` from your IDE or from a terminal. After a -few seconds, a gui should appear on the screen with a circular road -network. Click on the play -button on the top-left corner of the gui, and the network will -be filled with vehicles, which then begin to accelerate. - -As we can see, vehicles are not free-flowing in the ring. Instead, they seem to -generate stop-and-go waves in the ring, which forces all vehicles to slow down -constantly and prevents them from attaining their ideal equilibrium speeds. - - -6. Running an Experiment with Autonomy -====================================== - -Finally, we will attempt to add autonomous vehicles in the ring road. We -will begin by adding a single autonomous vehicles, in hopes that this -vehicle may be able to learn to attenuate the waves we witnessed in section 5. - -6.1 Creating a Gym Environment ------------------------------- - -Unlike in section 5, we will not rely on Flow's ``SumoExperiment`` -object to run experiments, but rather we will create a Gym Environment -and run it on ``rllab``. - -Create a new script entitled -``my_rl_experiment.py`` and import the generator and scenario -subclasses, in addition to the dynamical model provided by Flow, as -you had done in section 5.1 for the control experiment: - -:: - - # these are the classes I created - from my_generator import myGenerator - from my_scenario import myScenario - - # for possible mathematical operations we may want to perform - import numpy as np - - # input objects to my classes - from flow.core.params import SumoParams, EnvParams, InitialConfig, NetParams - from flow.core.vehicles import Vehicles - - # acceleration and lane-changing controllers for human-driven vehicles - from flow.controllers.car_following_models import * - from flow.controllers.lane_change_controllers import * - from flow.controllers.routing_controllers import * - -A new controller that is used in this experiment and needed in the case -of mixed-autonomy is the ``RLController``, located in -``flow.controllers.rlcontroller``. Any types of vehicles with this -controller will act as reinforcement learning agent(s). - -:: - - from flow.controllers.rlcontroller import RLController - -In additon, we will need several functions from ``rllab``: - -:: - - from rllab.envs.normalized_env import normalize - from rllab.misc.instrument import run_experiment_lite - from rllab.algos.trpo import TRPO - from rllab.baselines.linear_feature_baseline import LinearFeatureBaseline - from rllab.policies.gaussian_mlp_policy import GaussianMLPPolicy - from rllab.envs.gym_env import GymEnv - -Next, we define a function called ``run_task`` that will -be used to create and run our gym environment: - -:: - - def run_task(v): - -Similar to section 5, we must now define the necessary input variables -to the generator, scenario, and environment classes. These variable will -largely remain unchanged from section 5, but with the addition of a few -components. - -For one, in ``sumo_params`` we will want to specify an aggressive -SUMO-defined speed mode for rl vehicles, which will prevent SUMO from enforcing -a safe velocity upper bound on the autonomous vehicle, but may lead to the -autonomous vehicles crashing into the vehicles ahead of them. This is -done by setting "rl\_sm" to "aggressive". - -Moreover, in order to run rollouts with a max path length of 1500 steps -(i.e. 150 s), we set "num\_steps" in ``env_params`` to 1500. Also, in ordr to -satisfy the reward function we specified in `section 4.6`_, we set -"target\_velocity" in ``env_params`` to 8 m/s -(which far beyond the expected equilibrium velocity). - -Finally we introduce an autonomous (rl) vehicle into the network by -reducing the number of human vehicles by 1 and add a element to the -``vehicles`` object to include a vehicle with the acceleration controller -``RLController``. - -The final set of input variables are as follows: - -:: - - sumo_params = SumoParams(time_step=0.1, rl_speed_mode="aggressive", - sumo_binary="sumo-gui") - - additional_env_params = {"target_velocity": 8, "max-deacc": 3, "max-acc": 3, "num_steps": 1000} - env_params = EnvParams(additional_params=additional_env_params) - - additional_net_params = {"radius": 230 / (2*np.pi), "lanes": 1, "speed_limit": 30} - net_params = NetParams(additional_params=additional_net_params) - - initial_config = InitialConfig(bunching=20) - - vehicles = Vehicles() - vehicles.add_vehicles(veh_id="rl", - acceleration_controller=(RLController, {}), - routing_controller=(ContinuousRouter, {}), - num_vehicles=1) - vehicles.add_vehicles(veh_id="human", - acceleration_controller=(IDMController, {}), - routing_controller=(ContinuousRouter, {}), - num_vehicles=21) - -Creating the scenario does not change between this section and the last. -Calling our scenario "stabilizing-the-ring", the scenario class is -initialized as follows: - -:: - - scenario = myScenario("stabilizing-the-ring", myGenerator, vehicles, net_params, - initial_config) - -The environment, however, is no longer defined in the same manner. -Instead, a variable called env\_name is specified with the name of the -environment you created, and the list of parameters are placed into a -tuple: - -:: - - env_name = "myEnvironment" - pass_params = (env_name, sumo_params, vehicles, env_params, net_params, - initial_config, scenario) - -Then, the Gym Environment, parameterized by ``pass_params``, is initialized -as follows: - -:: - - env = GymEnv(env_name, record_video=False, register_params=pass_params) - -6.2 Specifying the Necessary rllab Components ---------------------------------------------- - -We use linear feature baselines and Trust Region Policy Optimization for -learning the policy, with discount factor :math:`\gamma = 0.999`, and step -size 0.01. A diagonal Gaussian MLP policy is used with hidden layers -(100, 50, 25) and tanh non-linearity. This is done within your script by adding -the following lines of code to the ``run_task`` function: - -:: - - horizon = env.horizon - env = normalize(env) - - policy = GaussianMLPPolicy( - env_spec=env.spec, - hidden_sizes=(100, 50, 25) - ) - - baseline = LinearFeatureBaseline(env_spec=env.spec) - - algo = TRPO( - env=env, - policy=policy, - baseline=baseline, - batch_size=15000, - max_path_length=env.horizon, - n_itr=300, - # whole_paths=True, - discount=0.999, - ) - algo.train(), - -6.3 Setting up the Experiment ------------------------------ - -Once the function run\_task is complete, we are able to wrap up the -script by calling ``rllab`` to run the experiment. This is done through -the use of the ``run_experiment_lite`` function. We choose to run the -experiment locally with one worker for sampling and a seed value of 5. -Also, we would like to keep track of the policy parameters from all -iterations. - -:: - - run_experiment_lite( - run_task, - # Number of parallel workers for sampling - n_parallel=1, - # Keeps the snapshot parameters for all iterations - snapshot_mode="all", - # Specifies the seed for the experiment. If this is not provided, a random seed - # will be used - seed=5, - mode="local", - exp_prefix="stabilizing-the-ring", - ) - -Note that, when using Python editors such as PyCharm, it may be necessary to -specify the path to the location of ``rllab``'s python command within -``run_experiment_lite`` . This will look something similar to: - -:: - - python_command="/envs/rllab-distributed/bin/python3.5" - -6.4 Running the Mixed-Autonomy Experiment ------------------------------------------ - -We are finally ready to run our first experiment with reinforcement learning -autonomous agents! Run the script and click on the "Play" button on sumo's gui -as you had done in section 5. The experiment will now run for a maximum of 300 -iterations (as we had specified); however, the experiments converges much sooner. -In fact, by around the 150th iteration, we notice that the vehicle had learned -to stop crashing completely, and that the vehicles in the ring seem to be -completely free-flowing, without the nuisance of stop-and-go waves. diff --git a/examples/__init__.py b/examples/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/examples/rllib/test_rllib.py b/examples/rllib/test_rllib.py deleted file mode 100644 index 05843dfe3..000000000 --- a/examples/rllib/test_rllib.py +++ /dev/null @@ -1,133 +0,0 @@ -""" -File used for quick tests of whether the code is working on large machines -""" - -import json - -import ray -import ray.rllib.ppo as ppo -from ray.tune import run_experiments -from ray.tune.registry import register_env - -from flow.utils.registry import make_create_env -from flow.utils.rllib import FlowParamsEncoder -from flow.core.params import SumoParams, EnvParams, InitialConfig, NetParams -from flow.core.vehicles import Vehicles -from flow.controllers.car_following_models import IDMController -from flow.controllers.routing_controllers import ContinuousRouter -from flow.controllers.rlcontroller import RLController -from flow.scenarios.figure8.figure8_scenario import ADDITIONAL_NET_PARAMS - -# time horizon of a single rollout -HORIZON = 1500 -# number of rollouts per training iteration -N_ROLLOUTS = 20 -# number of parallel workers -PARALLEL_ROLLOUTS = 20 - -# We place one autonomous vehicle and 13 human-driven vehicles in the network -vehicles = Vehicles() -vehicles.add(veh_id="human", - acceleration_controller=(IDMController, {"noise": 0.2}), - routing_controller=(ContinuousRouter, {}), - speed_mode="no_collide", - num_vehicles=13) -vehicles.add(veh_id="rl", - acceleration_controller=(RLController, {}), - routing_controller=(ContinuousRouter, {}), - speed_mode="no_collide", - num_vehicles=1) - -flow_params = dict( - # name of the experiment - exp_tag="figure_eight_intersection_control", - - # name of the flow environment the experiment is running on - env_name="AccelEnv", - - # name of the scenario class the experiment is running on - scenario="Figure8Scenario", - - # name of the generator used to create/modify network configuration files - generator="Figure8Generator", - - # sumo-related parameters (see flow.core.params.SumoParams) - sumo=SumoParams( - sim_step=0.1, - sumo_binary="sumo", - ), - - # environment related parameters (see flow.core.params.EnvParams) - env=EnvParams( - horizon=HORIZON, - warmup_steps=750, - additional_params={ - "target_velocity": 20, - "max_accel": 3, - "max_decel": 3, - }, - ), - - # network-related parameters (see flow.core.params.NetParams and the - # scenario's documentation or ADDITIONAL_NET_PARAMS component) - net=NetParams( - no_internal_links=False, - additional_params=ADDITIONAL_NET_PARAMS, - ), - - # vehicles to be placed in the network at the start of a rollout (see - # flow.core.vehicles.Vehicles) - veh=vehicles, - - # parameters specifying the positioning of vehicles upon initialization/ - # reset (see flow.core.params.InitialConfig) - initial=InitialConfig(), -) - - -if __name__ == "__main__": - ray.init(num_cpus=PARALLEL_ROLLOUTS, redirect_output=False) - - config = ppo.DEFAULT_CONFIG.copy() - config["num_workers"] = PARALLEL_ROLLOUTS - config["timesteps_per_batch"] = HORIZON * N_ROLLOUTS - config["gamma"] = 0.999 # discount rate - config["model"].update({"fcnet_hiddens": [100, 50, 25]}) - config["use_gae"] = True - config["lambda"] = 0.97 - config["sgd_batchsize"] = min(16 * 1024, config["timesteps_per_batch"]) - config["kl_target"] = 0.02 - config["num_sgd_iter"] = 10 - config["horizon"] = HORIZON - config["observation_filter"] = "NoFilter" - - # save the flow params for replay - flow_json = json.dumps(flow_params, cls=FlowParamsEncoder, sort_keys=True, - indent=4) - config['env_config']['flow_params'] = flow_json - - create_env, env_name = make_create_env(params=flow_params, version=0) - - # Register as rllib env - register_env(env_name, create_env) - - trials = run_experiments({ - "figure_eight": { - "run": "PPO", - "env": env_name, - "config": { - **config - }, - "checkpoint_freq": 1, - "max_failures": 999, - "stop": { - "training_iteration": 1 - }, - "repeat": 1, - "trial_resources": { - "cpu": 1, - "gpu": 0, - "extra_cpu": PARALLEL_ROLLOUTS - 1, - }, - }, - }) diff --git a/examples/sumo/bay_bridge.py b/examples/sumo/bay_bridge.py new file mode 100644 index 000000000..7aba3185f --- /dev/null +++ b/examples/sumo/bay_bridge.py @@ -0,0 +1,149 @@ +import os +import urllib.request + +from flow.core.params import SumoParams, EnvParams, NetParams, InitialConfig, \ + SumoCarFollowingParams, SumoLaneChangeParams, InFlows +from flow.core.vehicles import Vehicles +from flow.core.traffic_lights import TrafficLights + +from flow.core.experiment import SumoExperiment +from flow.envs.bay_bridge import BayBridgeEnv +from flow.scenarios.bay_bridge.gen import BayBridgeGenerator +from flow.scenarios.bay_bridge.scenario import BayBridgeScenario +from flow.controllers import SumoCarFollowingController, BayBridgeRouter + +NETFILE = os.path.join(os.path.dirname(os.path.abspath(__file__)), + "bay_bridge.net.xml") + + +def bay_bridge_example(sumo_binary=None, + use_inflows=False, + use_traffic_lights=False): + """ + Performs a simulation of human-driven vehicle on the Oakland-San Francisco + Bay Bridge. + + Parameters + ---------- + sumo_binary: bool, optional + specifies whether to use sumo's gui during execution + use_inflows: bool, optional + whether to activate inflows from the peripheries of the network + use_traffic_lights: bool, optional + whether to activate the traffic lights in the scenario + + Returns + ------- + exp: flow.core.SumoExperiment type + A non-rl experiment demonstrating the performance of human-driven + vehicles simulated by sumo on the Bay Bridge. + """ + sumo_params = SumoParams(sim_step=0.6, + overtake_right=True) + + if sumo_binary is not None: + sumo_params.sumo_binary = sumo_binary + + sumo_car_following_params = SumoCarFollowingParams(speedDev=0.2) + sumo_lc_params = SumoLaneChangeParams( + lcAssertive=20, + lcPushy=0.8, + lcSpeedGain=4.0, + model="LC2013", + # lcKeepRight=0.8 + ) + + vehicles = Vehicles() + vehicles.add(veh_id="human", + acceleration_controller=(SumoCarFollowingController, {}), + routing_controller=(BayBridgeRouter, {}), + speed_mode="all_checks", + lane_change_mode="no_lat_collide", + sumo_car_following_params=sumo_car_following_params, + sumo_lc_params=sumo_lc_params, + num_vehicles=1400) + + additional_env_params = {} + env_params = EnvParams(additional_params=additional_env_params) + + traffic_lights = TrafficLights() + + inflow = InFlows() + + if use_inflows: + # south + inflow.add(veh_type="human", edge="183343422", vehsPerHour=528, + departLane="0", departSpeed=20) + inflow.add(veh_type="human", edge="183343422", vehsPerHour=864, + departLane="1", departSpeed=20) + inflow.add(veh_type="human", edge="183343422", vehsPerHour=600, + departLane="2", departSpeed=20) + + inflow.add(veh_type="human", edge="393649534", probability=0.1, + departLane="0", departSpeed=20) # no data for this + + # west + inflow.add(veh_type="human", edge="11189946", vehsPerHour=1752, + departLane="0", departSpeed=20) + inflow.add(veh_type="human", edge="11189946", vehsPerHour=2136, + departLane="1", departSpeed=20) + inflow.add(veh_type="human", edge="11189946", vehsPerHour=576, + departLane="2", departSpeed=20) + + # north + inflow.add(veh_type="human", edge="28413687#0", vehsPerHour=2880, + departLane="0", departSpeed=20) + inflow.add(veh_type="human", edge="28413687#0", vehsPerHour=2328, + departLane="1", departSpeed=20) + inflow.add(veh_type="human", edge="28413687#0", vehsPerHour=3060, + departLane="2", departSpeed=20) + inflow.add(veh_type="human", edge="11198593", probability=0.1, + departLane="0", departSpeed=20) # no data for this + inflow.add(veh_type="human", edge="11197889", probability=0.1, + departLane="0", departSpeed=20) # no data for this + + # midway through bridge + inflow.add(veh_type="human", edge="35536683", probability=0.1, + departLane="0", departSpeed=20) # no data for this + + net_params = NetParams(in_flows=inflow, + no_internal_links=False) + net_params.netfile = NETFILE + + # download the netfile from AWS + if use_traffic_lights: + my_url = "https://s3-us-west-1.amazonaws.com/flow.netfiles/" \ + "bay_bridge_TL_all_green.net.xml" + else: + my_url = "https://s3-us-west-1.amazonaws.com/flow.netfiles/" \ + "bay_bridge_junction_fix.net.xml" + my_file = urllib.request.urlopen(my_url) + data_to_write = my_file.read() + + with open(os.path.join(os.path.dirname(os.path.abspath(__file__)), + NETFILE), "wb+") as f: + f.write(data_to_write) + + initial_config = InitialConfig(spacing="uniform", + min_gap=15) + + scenario = BayBridgeScenario(name="bay_bridge", + generator_class=BayBridgeGenerator, + vehicles=vehicles, + traffic_lights=traffic_lights, + net_params=net_params, + initial_config=initial_config) + + env = BayBridgeEnv(env_params, sumo_params, scenario) + + return SumoExperiment(env, scenario) + + +if __name__ == "__main__": + # import the experiment variable + exp = bay_bridge_example(sumo_binary="sumo-gui", + use_inflows=False, + use_traffic_lights=False) + + # run for a set number of rollouts / time steps + exp.run(1, 1500) diff --git a/examples/sumo/bay_bridge_toll.py b/examples/sumo/bay_bridge_toll.py new file mode 100644 index 000000000..006ce0051 --- /dev/null +++ b/examples/sumo/bay_bridge_toll.py @@ -0,0 +1,107 @@ +import os +import urllib.request + +from flow.core.params import SumoParams, EnvParams, NetParams, InitialConfig, \ + SumoLaneChangeParams, SumoCarFollowingParams, InFlows +from flow.core.vehicles import Vehicles + +from flow.core.experiment import SumoExperiment +from flow.envs.bay_bridge import BayBridgeEnv +from flow.scenarios.bay_bridge_toll.gen import BayBridgeTollGenerator +from flow.scenarios.bay_bridge_toll.scenario import BayBridgeTollScenario +from flow.controllers import SumoCarFollowingController, BayBridgeRouter + +NETFILE = os.path.join(os.path.dirname(os.path.abspath(__file__)), + "bottleneck.net.xml") + + +def bay_bridge_bottleneck_example(sumo_binary=None, + use_traffic_lights=False): + """ + Performs a non-RL simulation of the bottleneck portion of the Oakland-San + Francisco Bay Bridge. This consists of the toll booth and sections of the + road leading up to it. + Parameters + ---------- + sumo_binary: bool, optional + specifies whether to use sumo's gui during execution + use_traffic_lights: bool, optional + whether to activate the traffic lights in the scenario + Note + ---- + Unlike the bay_bridge_example, inflows are always activated here. + """ + sumo_params = SumoParams(sim_step=0.4, + overtake_right=True) + + if sumo_binary is not None: + sumo_params.sumo_binary = sumo_binary + + sumo_car_following_params = SumoCarFollowingParams(speedDev=0.2) + sumo_lc_params = SumoLaneChangeParams( + model="LC2013", lcCooperative=0.2, lcSpeedGain=15) + + vehicles = Vehicles() + + vehicles.add(veh_id="human", + acceleration_controller=(SumoCarFollowingController, {}), + routing_controller=(BayBridgeRouter, {}), + speed_mode="all_checks", + lane_change_mode="no_lat_collide", + sumo_car_following_params=sumo_car_following_params, + sumo_lc_params=sumo_lc_params, + num_vehicles=50) + + additional_env_params = {} + env_params = EnvParams(additional_params=additional_env_params) + + inflow = InFlows() + + inflow.add(veh_type="human", edge="393649534", probability=0.2, + departLane="random", departSpeed=10) + inflow.add(veh_type="human", edge="4757680", probability=0.2, + departLane="random", departSpeed=10) + inflow.add(veh_type="human", edge="32661316", probability=0.2, + departLane="random", departSpeed=10) + inflow.add(veh_type="human", edge="90077193#0", vehs_per_hour=2000, + departLane="random", departSpeed=10) + + net_params = NetParams(in_flows=inflow, + no_internal_links=False, + netfile=NETFILE) + + # download the netfile from AWS + if use_traffic_lights: + my_url = "https://s3-us-west-1.amazonaws.com/flow.netfiles/" \ + "bay_bridge_TL_all_green.net.xml" + else: + my_url = "https://s3-us-west-1.amazonaws.com/flow.netfiles/" \ + "bay_bridge_junction_fix.net.xml" + my_file = urllib.request.urlopen(my_url) + data_to_write = my_file.read() + + with open(os.path.join(os.path.dirname(os.path.abspath(__file__)), + NETFILE), "wb+") as f: + f.write(data_to_write) + + initial_config = InitialConfig(spacing="uniform", # "random", + min_gap=15) + + scenario = BayBridgeTollScenario(name="bay_bridge_toll", + generator_class=BayBridgeTollGenerator, + vehicles=vehicles, + net_params=net_params, + initial_config=initial_config) + + env = BayBridgeEnv(env_params, sumo_params, scenario) + + return SumoExperiment(env, scenario) + + +if __name__ == "__main__": + # import the experiment variable + exp = bay_bridge_bottleneck_example(sumo_binary="sumo-gui", + use_traffic_lights=False) + + # run for a set number of rollouts / time steps + exp.run(1, 1500) diff --git a/flow/controllers/car_following_models.py b/flow/controllers/car_following_models.py index c1741219f..5bd679329 100755 --- a/flow/controllers/car_following_models.py +++ b/flow/controllers/car_following_models.py @@ -297,7 +297,6 @@ def __init__(self, b=1.5, delta=4, s0=2, - s1=0, time_delay=0.0, dt=0.1, noise=0, @@ -321,8 +320,6 @@ def __init__(self, acceleration exponent (default: 4) s0: float, optional linear jam distance, in m (default: 2) - s1: float, optional - nonlinear jam distance, in m (default: 0) dt: float, optional timestep, in s (default: 0.1) noise: float, optional @@ -340,7 +337,6 @@ def __init__(self, self.b = b self.delta = delta self.s0 = s0 - self.s1 = s1 self.dt = dt def get_accel(self, env): diff --git a/flow/core/experiment.py b/flow/core/experiment.py index bb2f65861..35aa33578 100755 --- a/flow/core/experiment.py +++ b/flow/core/experiment.py @@ -39,9 +39,9 @@ def run(self, num_runs, num_steps, rl_actions=None, convert_to_csv=False): number of runs the experiment should perform num_steps: int number of steps to be performs in each run of the experiment - rl_actions: list or numpy ndarray, optional - actions to be performed by rl vehicles in the network (if there - are any) + rl_actions: method, optional + maps states to actions to be performed by the RL agents (if + there are any) convert_to_csv: bool Specifies whether to convert the emission file created by sumo into a csv file @@ -51,7 +51,8 @@ def run(self, num_runs, num_steps, rl_actions=None, convert_to_csv=False): """ info_dict = {} if rl_actions is None: - rl_actions = [] + def rl_actions(*_): + return [] rets = [] mean_rets = [] @@ -65,9 +66,9 @@ def run(self, num_runs, num_steps, rl_actions=None, convert_to_csv=False): ret = 0 ret_list = [] vehicles = self.env.vehicles - self.env.reset() + state = self.env.reset() for j in range(num_steps): - state, reward, done, _ = self.env.step(rl_actions) + state, reward, done, _ = self.env.step(rl_actions(state)) vel[j] = np.mean(vehicles.get_speed(vehicles.get_ids())) ret += reward ret_list.append(reward) diff --git a/flow/envs/__init__.py b/flow/envs/__init__.py index e0699e88a..31e748642 100755 --- a/flow/envs/__init__.py +++ b/flow/envs/__init__.py @@ -1,4 +1,7 @@ from flow.envs.base_env import Env +from flow.envs.bay_bridge import BayBridgeEnv +from flow.envs.bottleneck_env import BottleNeckAccelEnv, BottleneckEnv, \ + DesiredVelocityEnv from flow.envs.green_wave_env import TrafficLightGridEnv, \ PO_TrafficLightGridEnv, GreenWaveTestEnv from flow.envs.loop.lane_changing import LaneChangeAccelEnv, \ @@ -8,8 +11,11 @@ from flow.envs.loop.wave_attenuation import WaveAttenuationEnv, \ WaveAttenuationPOEnv from flow.envs.merge import WaveAttenuationMergePOEnv +from flow.envs.test import TestEnv __all__ = ["Env", "AccelEnv", "LaneChangeAccelEnv", "LaneChangeAccelPOEnv", "GreenWaveTestEnv", "GreenWaveTestEnv", "WaveAttenuationMergePOEnv", - "TwoLoopsMergeEnv", "WaveAttenuationEnv", "WaveAttenuationPOEnv", - "TrafficLightGridEnv", "PO_TrafficLightGridEnv"] + "TwoLoopsMergeEnv", "BottleneckEnv", "BottleNeckAccelEnv", + "WaveAttenuationEnv", "WaveAttenuationPOEnv", "TrafficLightGridEnv", + "PO_TrafficLightGridEnv", "DesiredVelocityEnv", "TestEnv", + "BayBridgeEnv"] diff --git a/flow/envs/bay_bridge/__init__.py b/flow/envs/bay_bridge/__init__.py new file mode 100644 index 000000000..d5802d7e0 --- /dev/null +++ b/flow/envs/bay_bridge/__init__.py @@ -0,0 +1,3 @@ +from flow.envs.bay_bridge.base import BayBridgeEnv + +__all__ = ["BayBridgeEnv"] diff --git a/flow/envs/bay_bridge/base.py b/flow/envs/bay_bridge/base.py new file mode 100644 index 000000000..a87de7098 --- /dev/null +++ b/flow/envs/bay_bridge/base.py @@ -0,0 +1,211 @@ +import numpy as np +from collections import defaultdict + +from flow.envs import Env + +EDGE_LIST = ['11198593', '236348360#1', '157598960', '11415208', '236348361', + '11198599', '35536683', '11198595.0', '11198595.656.0', "gneE5", + '340686911#3', '23874736', '119057701', '517934789', '236348364', + '124952171', "gneE0", "11198599", "124952182.0", '236348360#0', + '497579295', '340686911#2.0', '340686911#1', '394443191', + '322962944', "32661309#1.0", "90077193#1.777", "90077193#1.0", + "90077193#1.812", "gneE1", "183343422", "393649534", "32661316", + "4757680", "124952179", "11189946", "119058993", "28413679", + "11197898", "123741311", "123741303", "90077193#0", "28413687#0", + "28413687#1", "11197889", "123741382#0", "123741382#1", "gneE3", + "340686911#0.54.0", "340686911#0.54.54.0", + "340686911#0.54.54.127.0", "340686911#2.35"] + +MAX_LANES = 24 +NUM_EDGES = len(EDGE_LIST) +OBS_SPACE = 4 + 2 * NUM_EDGES + 4 * MAX_LANES +NUM_TRAFFIC_LIGHTS = 14 + +# number of vehicles a traffic light can observe in each lane +NUM_OBSERVED = 10 +EDGE_BEFORE_TOLL = "gneE3" +TB_TL_ID = "gneJ4" +EDGE_AFTER_TOLL = "340686911#0.54.0" +NUM_TOLL_LANES = 20 +TOLL_BOOTH_AREA = 100 + +EDGE_BEFORE_RAMP_METER = "340686911#0.54.54.0" +EDGE_AFTER_RAMP_METER = "340686911#0.54.54.127.0" +NUM_RAMP_METERS = 14 +RAMP_METER_AREA = 80 + +MEAN_SECONDS_WAIT_AT_FAST_TRACK = 3 +MEAN_SECONDS_WAIT_AT_TOLL = 15 +FAST_TRACK_ON = range(6, 11) + + +class BayBridgeEnv(Env): + """Base environment class for Bay Bridge scenarios. + + This class is responsible for mimicking the effects of the + + States + No observations are issued by this class (i.e. empty list). + + Actions + No actions are issued by this class. + + Rewards + The reward is the average speed of vehicles in the network + (temporarily). + + Termination + A rollout is terminated if the time horizon is reached or if two + vehicles collide into one another. + """ + + def __init__(self, env_params, sumo_params, scenario): + self.num_rl = scenario.vehicles.num_rl_vehicles + super().__init__(env_params, sumo_params, scenario) + self.edge_dict = defaultdict(list) + self.cars_waiting_for_toll = dict() + self.cars_before_ramp = dict() + self.toll_wait_time = np.abs( + np.random.normal(MEAN_SECONDS_WAIT_AT_TOLL / self.sim_step, + 4 / self.sim_step, NUM_TOLL_LANES)) + self.tl_state = "" + self.disable_tb = False + self.disable_ramp_metering = False + + if "disable_tb" in env_params.additional_params: + self.disable_tb = env_params.get_additional_param("disable_tb") + + if "disable_ramp_metering" in env_params.additional_params: + self.disable_ramp_metering = env_params.get_additional_param( + "disable_ramp_metering") + + def additional_command(self): + super().additional_command() + # build a list of vehicles and their edges and positions + self.edge_dict = defaultdict(list) + # update the dict with all the edges in edge_list so we can look + # forward for edges + self.edge_dict.update((k, [[] for _ in range(MAX_LANES)]) + for k in EDGE_LIST) + for veh_id in self.vehicles.get_ids(): + edge = self.vehicles.get_edge(veh_id) + if edge not in self.edge_dict: + self.edge_dict.update({edge: [[] for _ in range(MAX_LANES)]}) + lane = self.vehicles.get_lane(veh_id) # integer + pos = self.vehicles.get_position(veh_id) + + # perform necessary lane change actions to keep vehicle in the + # right route + self.edge_dict[edge][lane].append((veh_id, pos)) + if edge == "124952171" and lane == 1: + self.apply_lane_change([veh_id], direction=[1]) + + if not self.disable_tb: + self.apply_toll_bridge_control() + if not self.disable_ramp_metering: + self.ramp_meter_lane_change_control() + + def ramp_meter_lane_change_control(self): + cars_that_have_left = [] + for veh_id in self.cars_before_ramp: + if self.vehicles.get_edge(veh_id) == EDGE_AFTER_RAMP_METER: + lane_change_mode = self.cars_before_ramp[veh_id][ + "lane_change_mode"] + color = self.cars_before_ramp[veh_id]["color"] + self.traci_connection.vehicle.setColor(veh_id, color) + self.traci_connection.vehicle.setLaneChangeMode( + veh_id, lane_change_mode) + + cars_that_have_left.append(veh_id) + + for veh_id in cars_that_have_left: + self.cars_before_ramp.__delitem__(veh_id) + + for lane in range(NUM_RAMP_METERS): + cars_in_lane = self.edge_dict[EDGE_BEFORE_RAMP_METER][lane] + + for car in cars_in_lane: + veh_id, pos = car + if pos > RAMP_METER_AREA: + if veh_id not in self.cars_waiting_for_toll: + # Disable lane changes inside Toll Area + lane_change_mode = self.vehicles.get_lane_change_mode( + veh_id) + color = self.traci_connection.vehicle.getColor(veh_id) + self.cars_before_ramp[veh_id] = { + "lane_change_mode": lane_change_mode, + "color": color} + self.traci_connection.vehicle.setLaneChangeMode( + veh_id, 512) + self.traci_connection.vehicle.setColor( + veh_id, (0, 255, 255, 0)) + + def apply_toll_bridge_control(self): + cars_that_have_left = [] + for veh_id in self.cars_waiting_for_toll: + if self.vehicles.get_edge(veh_id) == EDGE_AFTER_TOLL: + lane = self.vehicles.get_lane(veh_id) + lane_change_mode = \ + self.cars_waiting_for_toll[veh_id]["lane_change_mode"] + color = self.cars_waiting_for_toll[veh_id]["color"] + self.traci_connection.vehicle.setColor(veh_id, color) + self.traci_connection.vehicle.setLaneChangeMode( + veh_id, lane_change_mode) + if lane not in FAST_TRACK_ON: + self.toll_wait_time[lane] = max(0, np.random.normal( + loc=MEAN_SECONDS_WAIT_AT_TOLL / self.sim_step, + scale=1 / self.sim_step)) + else: + self.toll_wait_time[lane] = max(0, np.random.normal( + loc=MEAN_SECONDS_WAIT_AT_FAST_TRACK / self.sim_step, + scale=1 / self.sim_step)) + + cars_that_have_left.append(veh_id) + + for veh_id in cars_that_have_left: + self.cars_waiting_for_toll.__delitem__(veh_id) + + traffic_light_states = ["G"] * NUM_TOLL_LANES + + for lane in range(NUM_TOLL_LANES): + cars_in_lane = self.edge_dict[EDGE_BEFORE_TOLL][lane] + + for car in cars_in_lane: + veh_id, pos = car + if pos > TOLL_BOOTH_AREA: + if veh_id not in self.cars_waiting_for_toll: + # Disable lane changes inside Toll Area + lc_mode = self.vehicles.get_lane_change_mode(veh_id) + color = self.traci_connection.vehicle.getColor(veh_id) + self.cars_waiting_for_toll[veh_id] = { + "lane_change_mode": lc_mode, "color": color} + self.traci_connection.vehicle.setLaneChangeMode( + veh_id, 512) + self.traci_connection.vehicle.setColor( + veh_id, (255, 0, 255, 0)) + else: + if pos > 120: + if self.toll_wait_time[lane] < 0: + traffic_light_states[lane] = "G" + else: + traffic_light_states[lane] = "r" + self.toll_wait_time[lane] -= 1 + + new_tls_state = "".join(traffic_light_states) + + if new_tls_state != self.tl_state: + self.tl_state = new_tls_state + self.traci_connection.trafficlight.setRedYellowGreenState( + tlsID=TB_TL_ID, state=new_tls_state) + + # TODO: decide on a good reward function + def compute_reward(self, state, rl_actions, **kwargs): + return np.mean(self.vehicles.get_speed(self.vehicles.get_ids())) + + """ The below methods need to be updated by child classes. """ + + def _apply_rl_actions(self, rl_actions): + pass + + def get_state(self): + return [] diff --git a/flow/envs/test.py b/flow/envs/test.py new file mode 100644 index 000000000..bfc8b2411 --- /dev/null +++ b/flow/envs/test.py @@ -0,0 +1,45 @@ +from flow.envs.base_env import Env +from gym.spaces.box import Box +import numpy as np + + +class TestEnv(Env): + """Test environment used to run simulations in the absence of autonomy. + + Required from env_params + None + + Optional from env_params + reward_fn : A reward function which takes an an input the environment + class and returns a real number. + + States + States are an empty list. + + Actions + No actions are provided to any RL agent. + + Rewards + The reward is zero at every step. + + Termination + A rollout is terminated if the time horizon is reached or if two + vehicles collide into one another. + """ + + @property + def action_space(self): + return Box(low=0, high=0, shape=0, dtype=np.float32) + + @property + def observation_space(self): + return Box(low=0, high=0, shape=0, dtype=np.float32) + + def _apply_rl_actions(self, rl_actions): + return + + def compute_reward(self, state, rl_actions, **kwargs): + return 0 + + def get_state(self, **kwargs): + return np.array([]) diff --git a/flow/scenarios/__init__.py b/flow/scenarios/__init__.py index 62fcbd9f9..6e82e01d6 100644 --- a/flow/scenarios/__init__.py +++ b/flow/scenarios/__init__.py @@ -2,6 +2,8 @@ from flow.scenarios.base_scenario import Scenario # custom generators +from flow.scenarios.bay_bridge.gen import BayBridgeGenerator +from flow.scenarios.bay_bridge_toll.gen import BayBridgeTollGenerator from flow.scenarios.bottleneck.gen import BottleneckGenerator from flow.scenarios.figure8.gen import Figure8Generator from flow.scenarios.grid.gen import SimpleGridGenerator @@ -12,6 +14,8 @@ from flow.scenarios.loop_merge.gen import TwoLoopOneMergingGenerator # custom scenarios +from flow.scenarios.bay_bridge.scenario import BayBridgeScenario +from flow.scenarios.bay_bridge_toll.scenario import BayBridgeTollScenario from flow.scenarios.bottleneck.scenario import BottleneckScenario from flow.scenarios.figure8.figure8_scenario import Figure8Scenario from flow.scenarios.grid.grid_scenario import SimpleGridScenario @@ -25,11 +29,13 @@ __all__ = ["Scenario"] # custom generators -__all__ += ["BottleneckGenerator", "Figure8Generator", "SimpleGridGenerator", +__all__ += ["BayBridgeGenerator", "BayBridgeTollGenerator", + "BottleneckGenerator", "Figure8Generator", "SimpleGridGenerator", "HighwayGenerator", "CircleGenerator", "MergeGenerator", "NetFileGenerator", "TwoLoopOneMergingGenerator"] # custom scenarios -__all__ += ["BottleneckScenario", "Figure8Scenario", "SimpleGridScenario", - "HighwayScenario", "LoopScenario", "MergeScenario", - "NetFileScenario", "TwoLoopsOneMergingScenario"] +__all__ += ["BayBridgeScenario", "BayBridgeTollScenario", "BottleneckScenario", + "Figure8Scenario", "SimpleGridScenario", "HighwayScenario", + "LoopScenario", "MergeScenario", "NetFileScenario", + "TwoLoopsOneMergingScenario"] diff --git a/flow/scenarios/bay_bridge/gen.py b/flow/scenarios/bay_bridge/gen.py new file mode 100644 index 000000000..1f331745b --- /dev/null +++ b/flow/scenarios/bay_bridge/gen.py @@ -0,0 +1,77 @@ +from flow.scenarios.netfile.gen import NetFileGenerator + + +class BayBridgeGenerator(NetFileGenerator): + """ + Bay Bridge generator. + """ + def specify_routes(self, net_params): + """ + Routes for vehicles moving through the bay bridge from Oakland to San + Francisco. + """ + rts = { + "11198593": ["11198593", "11198595.0"], + "157598960": ["157598960", "11198595.0"], + "11198595.0": ["11198595.0", "11198595.656.0"], + "11198595.656.0": ["11198595.656.0", "gneE5"], + "gneE5": ["gneE5", "340686911#2.0.13"], + "124952171": ["124952171", "11198599"], + "340686911#1": ["340686911#1", "340686911#2.0.0"], + "340686911#2.0.0": ["340686911#2.0.0", "340686911#2.0.13"], + "340686911#2.0.13": ["340686911#2.0.13", "340686911#2.35"], + "340686911#0.54.54.127.74": ["340686911#0.54.54.127.74", + "340686911#1"], + "340686911#3": ["340686911#3", "236348361"], + "236348361": ["236348361", "236348360#0"], + "236348360#0": ["236348360#0", "236348360#1"], + "236348360#0_1": ["236348360#0", "322962944"], + "236348360#1": ["236348360#1", "517934789"], + "517934789": ["517934789", "236348364"], + "236348364": ["236348364", "497579295"], + "35536683": ["35536683", "497579295"], + "497579295": ["497579295", "11415208"], + "11415208": ["11415208", "23874736"], + "119057701": ["119057701", "394443191"], + "23874736": ["23874736", "394443191"], + "183343422": ["183343422", "32661316"], + "183343422_1": ["183343422", "4757680"], + "393649534": ["393649534", "124952179"], + "32661316": ["32661316", "124952179"], + "124952179": ["124952179", "157598960"], + "124952179_1": ["124952179", "124952171"], + "4757680": ["4757680", "32661309#0"], + "11189946": ["11189946", "119058993"], + "119058993": ["119058993", "28413679"], + "28413679": ["28413679", "11197898"], + "11197898": ["11197898", "123741311"], + "123741311": ["123741311", "123741303"], + "123741303": ["123741303", "90077193#0"], + "28413687#0": ["28413687#0", "28413687#1"], + "28413687#1": ["28413687#1", "123741382#0"], + "11197889": ["11197889", "123741382#0"], + "123741382#0": ["123741382#0", "123741382#1"], + "123741382#1": ["123741382#1", "123741311"], + "394443191": ["394443191"], + "322962944": ["322962944"], + "90077193#0": ["90077193#0", "90077193#1.0"], + "11198599": ["11198599", "124952182.0"], + "124952182.0": ["124952182.0", "gneE0"], + "gneE0": ["gneE0", "90077193#1.777"], + "90077193#1.777": ["90077193#1.777", "90077193#1.812"], + "32661309#0": ["32661309#0", "32661309#1.0"], + "32661309#1.0": ["32661309#1.0", "gneE1"], + "gneE1": ["gneE1", "90077193#1.812"], + "90077193#1.0": ["90077193#1.0", "90077193#1.777"], + "90077193#1.812": ["90077193#1.812", "gneE3"], + "gneE3": ["gneE3", "340686911#0.54.0"], + "340686911#0.54.0": ["340686911#0.54.0", "340686911#0.54.54.0"], + "340686911#0.54.54.0": ["340686911#0.54.54.0", + "340686911#0.54.54.127.0"], + "340686911#0.54.54.127.0": ["340686911#0.54.54.127.0", + "340686911#0.54.54.127.74"], + "340686911#2.35": ["340686911#2.35", "340686911#3"] + + } + + return rts diff --git a/flow/scenarios/bay_bridge/scenario.py b/flow/scenarios/bay_bridge/scenario.py new file mode 100644 index 000000000..ed1b86b77 --- /dev/null +++ b/flow/scenarios/bay_bridge/scenario.py @@ -0,0 +1,31 @@ +from flow.scenarios.netfile.scenario import NetFileScenario + + +class BayBridgeScenario(NetFileScenario): + """ + A scenario used to simulate the bottleneck portion of the Bay Bridge. + """ + def generate_starting_positions(self, **kwargs): + """ + See parent class. + + Vehicles are only placed in the edges of the Bay Bridge moving from + Oakland to San Francisco. + """ + self.initial_config.edges_distribution = [ + '236348360#1', '157598960', + '11415208', '236348361', '11198599', + '11198595.0', '11198595.656.0', + '340686911#3', '23874736', '119057701', '517934789', + '236348364', '124952171', "gneE0", "11198599", "124952182.0", + '236348360#0', '497579295', '340686911#2.0.0', + '340686911#1', '394443191', '322962944', "32661309#1.0", + "90077193#1.777", "90077193#1.0", "90077193#1.812", "gneE1", + "32661316", "4757680", "124952179", + "119058993", "28413679", "11197898", "123741311", + "123741303", "90077193#0", "28413687#1", "11197889", + "123741382#0", "123741382#1", "gneE3", "340686911#0.54.0", + "340686911#0.54.54.0", "340686911#0.54.54.127.0", "340686911#2.35", + ] + + return super().generate_starting_positions(**kwargs) diff --git a/flow/scenarios/bay_bridge_toll/gen.py b/flow/scenarios/bay_bridge_toll/gen.py new file mode 100644 index 000000000..c66a407f7 --- /dev/null +++ b/flow/scenarios/bay_bridge_toll/gen.py @@ -0,0 +1,49 @@ +from flow.scenarios.netfile.gen import NetFileGenerator + + +class BayBridgeTollGenerator(NetFileGenerator): + """ + Bay Bridge bottleneck generator. + """ + def specify_routes(self, net_params): + """ + Routes for vehicles moving through the bay bridge from Oakland to San + Francisco. + """ + rts = { + "11198593": ["11198593", "11198595.0"], + "157598960": ["157598960", "11198595.0"], + "11198595.0": ["11198595.0", "11198595.656.0"], + "11198595.656.0": ["11198595.656.0", "gneE5"], + "gneE5": ["gneE5", "340686911#2.0.13"], + "124952171": ["124952171", "11198599"], + "340686911#1": ["340686911#1", "340686911#2.0.0"], + "340686911#2.0.0": ["340686911#2.0.0", "340686911#2.0.13"], + "340686911#0.54.54.127.74": ["340686911#0.54.54.127.74", + "340686911#1"], + "340686911#2.0.13": ["340686911#2.0.13", "340686911#2.35"], + "340686911#2.35": ["340686911#2.35"], + "393649534": ["393649534", "124952179"], + "32661316": ["32661316", "124952179"], + "124952179": ["124952179", "157598960"], + "124952179_1": ["124952179", "124952171"], + "4757680": ["4757680", "32661309#0"], + "90077193#0": ["90077193#0", "90077193#1.0"], + "11198599": ["11198599", "124952182.0"], + "124952182.0": ["124952182.0", "gneE0"], + "gneE0": ["gneE0", "90077193#1.777"], + "90077193#1.777": ["90077193#1.777", "90077193#1.812"], + "32661309#0": ["32661309#0", "32661309#1.0"], + "32661309#1.0": ["32661309#1.0", "gneE1"], + "gneE1": ["gneE1", "90077193#1.812"], + "90077193#1.0": ["90077193#1.0", "90077193#1.777"], + "90077193#1.812": ["90077193#1.812", "gneE3"], + "gneE3": ["gneE3", "340686911#0.54.0"], + "340686911#0.54.0": ["340686911#0.54.0", "340686911#0.54.54.0"], + "340686911#0.54.54.0": ["340686911#0.54.54.0", + "340686911#0.54.54.127.0"], + "340686911#0.54.54.127.0": ["340686911#0.54.54.127.0", + "340686911#0.54.54.127.74"], + } + + return rts diff --git a/flow/scenarios/bay_bridge_toll/scenario.py b/flow/scenarios/bay_bridge_toll/scenario.py new file mode 100644 index 000000000..8bc732d0d --- /dev/null +++ b/flow/scenarios/bay_bridge_toll/scenario.py @@ -0,0 +1,27 @@ +from flow.scenarios.netfile.scenario import NetFileScenario + + +class BayBridgeTollScenario(NetFileScenario): + """ + A scenario used to simulate the Bay Bridge. + """ + def generate_starting_positions(self, **kwargs): + """ + See parent class. + + Vehicles are only placed in the edges of the Bay Bridge moving from + Oakland to San Francisco. + """ + self.initial_config.edges_distribution = [ + '157598960', '11198599', + '11198595.0', '11198595.656.0', + '124952171', "gneE0", "11198599", "124952182.0", + '340686911#2.0.0', + '340686911#1', "32661309#1.0", + "90077193#1.777", "90077193#1.0", "90077193#1.812", "gneE1", + "124952179", + "gneE3", "340686911#0.54.0", + "340686911#0.54.54.0", "340686911#0.54.54.127.0", "340686911#2.35", + ] + + return super().generate_starting_positions(**kwargs) diff --git a/scripts/ray_autoscale.yaml b/scripts/ray_autoscale.yaml index 9097b6e67..e81b12bb2 100644 --- a/scripts/ray_autoscale.yaml +++ b/scripts/ray_autoscale.yaml @@ -5,11 +5,11 @@ cluster_name: test # # The minimum number of workers nodes to launch in addition to the head # node. This number should be >= 0. -min_workers: 2 # +min_workers: 0 # # The maximum number of workers nodes to launch in addition to the head # node. This takes precedence over min_workers. -max_workers: 2 +max_workers: 0 # The autoscaler will scale up the cluster to this target fraction of resource # usage. For example, if a cluster of 10 nodes is 100% busy and @@ -39,7 +39,7 @@ auth: # For more documentation on available fields, see: # http://boto3.readthedocs.io/en/latest/reference/services/ec2.html#EC2.ServiceResource.create_instances head_node: - InstanceType: m4.16xlarge + InstanceType: c4.4xlarge ImageId: ami-a2948fc2 # Flow AMI (Ubuntu) InstanceMarketOptions: MarketType: spot @@ -54,7 +54,7 @@ head_node: # For more documentation on available fields, see: # http://boto3.readthedocs.io/en/latest/reference/services/ec2.html#EC2.ServiceResource.create_instances worker_nodes: - InstanceType: m4.16xlarge + InstanceType: c4.4xlarge ImageId: ami-a2948fc2 # Flow AMI (Ubuntu) #Run workers on spot by default. Comment this out to use on-demand. @@ -68,17 +68,17 @@ worker_nodes: file_mounts: { # path to your repo and the desired branch name -#"/tmp/foo": "/.git/refs/heads/", -#"/tmp/foo2": "", -"/tmp/foo": "/Users/eugenevinitsky/Desktop/Research/Bayen/Code/rllab-multiagent/learning-traffic/.git/refs/heads/ars_runner", -"/tmp/foo2": "/Users/eugenevinitsky/.ssh/ray-autoscaler_1_us-west-1.pem", +#"/tmp/path": "/.git/refs/heads/", +#"/tmp/ray_autoscaler_key": "", +"/tmp/path": "/Users/eugenevinitsky/Desktop/Research/Bayen/Code/rllab-multiagent/learning-traffic/.git/refs/heads/ars_runner", +"/tmp/ray_autoscaler_key": "/Users/eugenevinitsky/.ssh/ray-autoscaler_1_us-west-1.pem", } setup_commands: # checkout your desired branch on all worker nodes # - cd learning-traffic && GIT_SSH_COMMAND="ssh -i ~/ray_bootstrap_key.pem" git fetch - - cd /tmp && cp foo2 ~/ray_autoscaler_key.pem - - cd flow-devel && GIT_SSH_COMMAND="ssh -i ~/ray_autoscaler_key.pem" git fetch && GIT_SSH_COMMAND="ssh -i ~/ray_autoscaler_key.pem" git checkout `cat /tmp/foo` + - cd /tmp && cp ray_autoscaler_key ~/ray_autoscaler_key.pem + - cd flow-devel && GIT_SSH_COMMAND="ssh -i ~/ray_autoscaler_key.pem" git fetch && GIT_SSH_COMMAND="ssh -i ~/ray_autoscaler_key.pem" git checkout `cat /tmp/path` - cd ray && git fetch eugene_upstream && git checkout add_ars && git pull - echo 'export PATH="/home/ubuntu/sumo/bin:$PATH"' >> ~/.bashrc - echo 'export SUMO_HOME="/home/ubuntu/sumo"' >> ~/.bashrc diff --git a/tests/fast_tests/test_controllers.py b/tests/fast_tests/test_controllers.py index d50a8594b..ca66d5d3e 100644 --- a/tests/fast_tests/test_controllers.py +++ b/tests/fast_tests/test_controllers.py @@ -211,8 +211,7 @@ def setUp(self): # add a few vehicles to the network using the requested model # also make sure that the input params are what is expected contr_params = {"v0": 30, "b": 1.5, "delta": 4, - "s0": 2, "s1": 0, - "noise": 0} + "s0": 2, "noise": 0} vehicles = Vehicles() vehicles.add( diff --git a/tests/fast_tests/test_experiment_base_class.py b/tests/fast_tests/test_experiment_base_class.py index d135db6d6..599018ac5 100644 --- a/tests/fast_tests/test_experiment_base_class.py +++ b/tests/fast_tests/test_experiment_base_class.py @@ -2,6 +2,9 @@ import os from flow.core.experiment import SumoExperiment +from flow.core.vehicles import Vehicles +from flow.controllers import IDMController, RLController, ContinuousRouter + from tests.setup_scripts import ring_road_exp_setup import numpy as np @@ -57,5 +60,36 @@ def runTest(self): np.testing.assert_array_almost_equal(vel1, vel2) +class TestRLActions(unittest.TestCase): + """ + Test that the rl_actions parameter acts as it should when it is specified, + and does not break the simulation when it is left blank. + """ + + def runTest(self): + def test_rl_actions(*_): + return [1] # actions are always an acceleration of 1 for one veh + + # create an environment using AccelEnv with 1 RL vehicle + vehicles = Vehicles() + vehicles.add(veh_id="rl", + acceleration_controller=(RLController, {}), + routing_controller=(ContinuousRouter, {}), + speed_mode="aggressive", + num_vehicles=1) + + env, scenario = ring_road_exp_setup(vehicles=vehicles) + + exp = SumoExperiment(env=env, scenario=scenario) + + exp.run(1, 10, rl_actions=test_rl_actions) + + # check that the acceleration of the RL vehicle was that specified by + # the rl_actions method + self.assertAlmostEqual(exp.env.vehicles.get_speed("rl_0"), 1, places=1) + + pass + + if __name__ == '__main__': unittest.main() From 86dfa8d9f4142e4a6e442bc08a25ab3f94725908 Mon Sep 17 00:00:00 2001 From: Nishant Date: Thu, 9 Aug 2018 17:30:32 -0700 Subject: [PATCH 04/25] initial tutorial 11 commit --- tutorials/tutorial11_rllab_ec2.ipynb | 129 +++++++++++++++++++++++++++ 1 file changed, 129 insertions(+) create mode 100644 tutorials/tutorial11_rllab_ec2.ipynb diff --git a/tutorials/tutorial11_rllab_ec2.ipynb b/tutorials/tutorial11_rllab_ec2.ipynb new file mode 100644 index 000000000..9b29ca077 --- /dev/null +++ b/tutorials/tutorial11_rllab_ec2.ipynb @@ -0,0 +1,129 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Exercise 11: Running rllab experiments on EC2\n", + "\n", + "This tutorial, a complement to tutorial 10, covers the process of running rllab experients on an Amazon EC2 instance. This tutorial assumes rllab has been installed correctly ([instructions](https://rllab.readthedocs.io/en/latest/user/installation.html)). " + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "First, follow the [rllab cluster setup instructions](https://rllab.readthedocs.io/en/latest/user/cluster.html) with region `us-west-1`. Modify `rllab/config_personal.py` to reference the most currently Flow Docker image (at the time of this writing, `evinitsky/flow`). \n", + "\n", + "Navigate to your `flow-devel` directory and modify `Makefile.template` per the instructions in that file. \n", + "\n", + "- The variable `RLLABDIR` should be the relative path from your `flow-devel` directory to \n", + "- " + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "collapsed": true + }, + "outputs": [], + "source": [] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Setting up AWS\n", + "\n", + "\n", + " - Pull `openai/rllab-distributed` repository and switch to production `sharedPolicyUpdate_release` branch\n", + " ```bash\n", + " git clone https://github.com/openai/rllab-distributed.git\n", + " cd rllab-distributed\n", + " git checkout sharedPolicyUpdate_release\n", + " ```\n", + " - Follow [rllab local setup instructions](https://rllab.readthedocs.io/en/latest/user/installation.html)\n", + " - Follow [rllab cluster setup instructions](http://rllab.readthedocs.io/en/latest/user/cluster.html)\n", + " - If prompted, region = us-west-1\n", + " - Note: the current Docker image path is \"evinitsky/flow-distributed\". Your `rllab-distributed/rllab/config_personal.py` should reflect that.\n", + " - (Optional): As desired, add to `config_personal.py` files and \n", + " directories that you do not need uploaded to EC2 for every \n", + " experiment by modifying `FAST_CODE_SYNC_IGNORES`.\n", + " - Go to `Makefile.template` in `learning-traffic/flow_dev` and update\n", + " the path to your rllab root directory (no trailing slash)\n", + " - The `flow_dev` reference in the Makefile might need to be updated to `flow`\n", + " - (See note below); Run `make prepare` \n", + " - Try an example! Run any experiment from `flow_dev/examples`, change\n", + " mode to “ec2”\n", + " - You can run it locally by changing the mode to local_docker. If this isn't working, make sure to check that your local docker image is the most current image. \n", + " - Log into AWS via: https://cathywu.signin.aws.amazon.com/console\n", + " - If you don’t see the instance you just launched (give it a few \n", + " minutes) running on AWS, then make sure your region is correct (go to\n", + " top right and change to `US West (N. California)` \n", + "\n", + "## Notes\n", + "\n", + "- When we run experiments on AWS, we create a new instance for each\n", + "seed and use the Docker image I created as the VM. Built into the rllab \n", + "script for running experiments in EC2 mode, we upload the rllab root \n", + "directory to AWS. This way, the AWS instance has access to all files it\n", + " might need to successfully run the experiment. Editing that code is\n", + " pretty complicated, so Cathy and I have decided on the following \n", + " workflow:\n", + " - All code modification will happen in the learning-traffic directory\n", + " - Before each experiment, run the command `make prepare` , which will\n", + " remove the flow_dev directory in rllab root and copy\n", + " `learning-traffic/flow_dev-dev/flow_dev` into your rllab root directory\n", + " - This means if you make modifications to flow_dev in the rllab\n", + " directory, they may be lost\n", + " - Before each experiment, always make sure you have a commit to that \n", + " exact snapshot of the `flow_dev` directory. This is because you may\n", + " modify flow_dev later. When you want to run `visualizer.py` , which is\n", + " our modified version of `sim_policy.py` , AKA when you want to \n", + " create rollout plots, you need the files in `rllab/flow_dev` to match\n", + " the files that were there when you originally ran the experiment.\n", + " So when you want to create rollout plots, you will checkout the\n", + " commit that matches when you ran the experiment and run make \n", + " prepare, then you can create rollout plots in the rllab directory.\n", + " - Ping me if there are issues!\n", + "- I recommend cleaning up your rllab directory, especially if you \n", + "notice you’re uploading a large size to AWS (it will tell you how many\n", + " MB you are uploading, should be < 5 MB). The command `make clean` \n", + " removes the debug directory (since so far we hardcoded that our SUMO\n", + " files go into that directory, this should be changed in the future) \n", + " and also all XML files in rllab root directory.\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "collapsed": true + }, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.5.2" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} From 5700337c4cc57d9a2c1fee6bba8587a0947d03fc Mon Sep 17 00:00:00 2001 From: Fangyu Wu Date: Thu, 9 Aug 2018 23:17:47 -0700 Subject: [PATCH 05/25] Add __version__ macro (#17) --- flow/__init__.py | 1 + flow/version.py | 1 + 2 files changed, 2 insertions(+) create mode 100644 flow/version.py diff --git a/flow/__init__.py b/flow/__init__.py index d0102bcdb..29aa7b0d0 100644 --- a/flow/__init__.py +++ b/flow/__init__.py @@ -1,3 +1,4 @@ +from .version import __version__ import logging from gym.envs.registration import register diff --git a/flow/version.py b/flow/version.py new file mode 100644 index 000000000..40692a7a9 --- /dev/null +++ b/flow/version.py @@ -0,0 +1 @@ +__version__="0.1.0" From f266a6bf354fb78658d03b557fa3cef186b128a8 Mon Sep 17 00:00:00 2001 From: AboudyKreidieh Date: Thu, 9 Aug 2018 23:35:07 -0700 Subject: [PATCH 06/25] cleaned up examples folder --- examples/rllab/bottlenecks.py | 138 ---------------------- examples/rllab/cooperative_merge.py | 36 ++++-- examples/rllab/figure_eight.py | 2 +- examples/rllib/cooperative_merge.py | 18 +-- examples/rllib/stabilizing_highway.py | 2 +- examples/rllib/velocity_bottleneck.py | 3 +- examples/sumo/bay_bridge_toll.py | 2 + examples/sumo/two_loops_merge_straight.py | 80 ------------- flow/envs/__init__.py | 4 +- flow/envs/loop/loop_merges.py | 2 +- tests/fast_tests/test_examples.py | 7 +- 11 files changed, 46 insertions(+), 248 deletions(-) delete mode 100644 examples/rllab/bottlenecks.py delete mode 100755 examples/sumo/two_loops_merge_straight.py diff --git a/examples/rllab/bottlenecks.py b/examples/rllab/bottlenecks.py deleted file mode 100644 index e6c0ab911..000000000 --- a/examples/rllab/bottlenecks.py +++ /dev/null @@ -1,138 +0,0 @@ -""" -(description) -""" - -from flow.core.params import SumoParams, EnvParams, NetParams, InitialConfig, \ - InFlows -from flow.core.vehicles import Vehicles -from flow.core.traffic_lights import TrafficLights - -from flow.scenarios.bottleneck.gen import BottleneckGenerator -from flow.scenarios.bottleneck.scenario import BottleneckScenario -from flow.controllers import RLController, SumoLaneChangeController, \ - ContinuousRouter -from flow.core.params import SumoLaneChangeParams - -from rllab.envs.gym_env import GymEnv -from rllab.envs.normalized_env import normalize -from rllab.misc.instrument import run_experiment_lite -from rllab.algos.trpo import TRPO -from rllab.baselines.linear_feature_baseline import LinearFeatureBaseline -from rllab.policies.gaussian_mlp_policy import GaussianMLPPolicy - -SCALING = 1 -DISABLE_TB = True -DISABLE_RAMP_METER = True -FLOW_RATE = 1500 * SCALING # inflow rate - -sumo_params = SumoParams(sim_step=0.5, sumo_binary="sumo") - -vehicles = Vehicles() - -vehicles.add(veh_id="rl", - acceleration_controller=(RLController, {}), - lane_change_controller=(SumoLaneChangeController, {}), - routing_controller=(ContinuousRouter, {}), - speed_mode=0b11111, - lane_change_mode=1621, - num_vehicles=4*SCALING, - sumo_lc_params=SumoLaneChangeParams()) -vehicles.add(veh_id="human", - speed_mode=0b11111, - lane_change_controller=(SumoLaneChangeController, {}), - routing_controller=(ContinuousRouter, {}), - lane_change_mode=512, - num_vehicles=15*SCALING) -vehicles.add(veh_id="rl2", - acceleration_controller=(RLController, {}), - lane_change_controller=(SumoLaneChangeController, {}), - routing_controller=(ContinuousRouter, {}), - speed_mode=0b11111, - lane_change_mode=1621, - num_vehicles=4*SCALING, - sumo_lc_params=SumoLaneChangeParams()) -vehicles.add(veh_id="human2", - speed_mode=0b11111, - lane_change_mode=512, - lane_change_controller=(SumoLaneChangeController, {}), - routing_controller=(ContinuousRouter, {}), - num_vehicles=15*SCALING) - -additional_env_params = {"target_velocity": 50, "num_steps": 150, - "disable_tb": True, "disable_ramp_metering": True, - "add_rl_if_exit": True} -env_params = EnvParams(additional_params=additional_env_params) - -inflow = InFlows() -inflow.add(veh_type="human", edge="1", vehsPerHour=FLOW_RATE, - departLane="random", departSpeed=10) - -traffic_lights = TrafficLights() -if not DISABLE_TB: - traffic_lights.add(node_id="2") -if not DISABLE_RAMP_METER: - traffic_lights.add(node_id="3") - -additional_net_params = {"scaling": SCALING} -net_params = NetParams(in_flows=inflow, - no_internal_links=False, - additional_params=additional_net_params) - -initial_config = InitialConfig(spacing="uniform", min_gap=5, - lanes_distribution=float("inf"), - edges_distribution=["2", "3", "4", "5"]) - -scenario = BottleneckScenario(name="bay_bridge_toll", - generator_class=BottleneckGenerator, - vehicles=vehicles, - net_params=net_params, - initial_config=initial_config, - traffic_lights=traffic_lights) - - -def run_task(*_): - env_name = "BottleneckEnv" - pass_params = (env_name, sumo_params, vehicles, env_params, - net_params, initial_config, scenario) - - env = GymEnv(env_name, record_video=False, register_params=pass_params) - horizon = env.horizon - env = normalize(env) - - policy = GaussianMLPPolicy( - env_spec=env.spec, - hidden_sizes=(100, 50, 25) - ) - - baseline = LinearFeatureBaseline(env_spec=env.spec) - - algo = TRPO( - env=env, - policy=policy, - baseline=baseline, - batch_size=20000, - max_path_length=horizon, - # whole_paths=True, - n_itr=400, - discount=0.995, - # step_size=0.01, - ) - algo.train() - - -exp_tag = "BottleNeckVerySmall" # experiment prefix - -for seed in [1]: # , 1, 5, 10, 73]: - run_experiment_lite( - run_task, - # Number of parallel workers for sampling - n_parallel=4, - # Only keep the snapshot parameters for the last iteration - snapshot_mode="all", - # Specifies the seed for the experiment. If this is not provided, a - # random seed will be used - seed=seed, - mode="local", - exp_prefix=exp_tag, - # plot=True, - ) diff --git a/examples/rllab/cooperative_merge.py b/examples/rllab/cooperative_merge.py index 02f214ad2..ec185b30a 100644 --- a/examples/rllab/cooperative_merge.py +++ b/examples/rllab/cooperative_merge.py @@ -17,13 +17,14 @@ SumoCarFollowingParams, SumoLaneChangeParams from flow.core.vehicles import Vehicles from flow.scenarios.loop_merge.gen import TwoLoopOneMergingGenerator -from flow.scenarios.loop_merge.scenario import TwoLoopsOneMergingScenario +from flow.scenarios.loop_merge.scenario import TwoLoopsOneMergingScenario, \ + ADDITIONAL_NET_PARAMS HORIZON = 300 def run_task(*_): - sumo_params = SumoParams(sim_step=0.2, sumo_binary="sumo") + sumo_params = SumoParams(sim_step=0.2, sumo_binary="sumo-gui") # note that the vehicles are added sequentially by the generator, # so place the merging vehicles after the vehicles in the ring @@ -65,14 +66,23 @@ def run_task(*_): ), sumo_lc_params=SumoLaneChangeParams()) - additional_env_params = {"target_velocity": 20, "max-deacc": -1.5, - "max-acc": 1} - env_params = EnvParams(horizon=HORIZON, - additional_params=additional_env_params) + env_params = EnvParams( + horizon=HORIZON, + additional_params={ + "max_accel": 3, + "max_decel": 3, + "target_velocity": 10, + "n_preceding": 2, + "n_following": 2, + "n_merging_in": 2, + } + ) - additional_net_params = {"ring_radius": 50, "lanes": 1, - "lane_length": 75, "speed_limit": 30, - "resolution": 40} + additional_net_params = ADDITIONAL_NET_PARAMS.copy() + additional_net_params["ring_radius"] = 50 + additional_net_params["inner_lanes"] = 1 + additional_net_params["outer_lanes"] = 1 + additional_net_params["lane_length"] = 75 net_params = NetParams( no_internal_links=False, additional_params=additional_net_params @@ -80,7 +90,7 @@ def run_task(*_): initial_config = InitialConfig( x0=50, - spacing="custom", + spacing="uniform", additional_params={"merge_bunching": 0} ) @@ -123,17 +133,17 @@ def run_task(*_): exp_tag = "cooperative_merge_example" # experiment prefix -for seed in [1, 5, 10, 56]: # , 1, 5, 10, 73]: +for seed in [1]: # , 5, 10, 56, 73]: run_experiment_lite( run_task, # Number of parallel workers for sampling - n_parallel=8, + n_parallel=1, # Only keep the snapshot parameters for the last iteration snapshot_mode="all", # Specifies the seed for the experiment. If this is not provided, a # random seed will be used seed=seed, - mode="ec2", + mode="local", # "ec2" exp_prefix=exp_tag, # plot=True, ) diff --git a/examples/rllab/figure_eight.py b/examples/rllab/figure_eight.py index 9d4b31241..10c04cbcc 100644 --- a/examples/rllab/figure_eight.py +++ b/examples/rllab/figure_eight.py @@ -19,7 +19,7 @@ def run_task(*_): sumo_params = SumoParams(sim_step=0.1, - sumo_binary="sumo") + sumo_binary="sumo-gui") vehicles = Vehicles() vehicles.add(veh_id="rl", diff --git a/examples/rllib/cooperative_merge.py b/examples/rllib/cooperative_merge.py index f88117a81..1935efec5 100644 --- a/examples/rllib/cooperative_merge.py +++ b/examples/rllib/cooperative_merge.py @@ -73,7 +73,7 @@ exp_tag="cooperative_merge", # name of the flow environment the experiment is running on - env_name="TwoLoopsMergeEnv", + env_name="TwoLoopsMergePOEnv", # name of the scenario class the experiment is running on scenario="TwoLoopsOneMergingScenario", @@ -91,9 +91,12 @@ env=EnvParams( horizon=HORIZON, additional_params={ - "target_velocity": 20, - "max_accel": 1, - "max_decel": 1.5, + "max_accel": 3, + "max_decel": 3, + "target_velocity": 10, + "n_preceding": 2, + "n_following": 2, + "n_merging_in": 2, }, ), @@ -103,14 +106,15 @@ no_internal_links=False, additional_params={ "ring_radius": 50, - "lanes": 1, "lane_length": 75, + "inner_lanes": 1, + "outer_lanes": 1, "speed_limit": 30, "resolution": 40, }, ), - # vehicles to be placed in the network at the start of a rollout (see +# vehicles to be placed in the network at the start of a rollout (see # flow.core.vehicles.Vehicles) veh=vehicles, @@ -118,7 +122,7 @@ # reset (see flow.core.params.InitialConfig) initial=InitialConfig( x0=50, - spacing="custom", + spacing="uniform", additional_params={ "merge_bunching": 0, }, diff --git a/examples/rllib/stabilizing_highway.py b/examples/rllib/stabilizing_highway.py index cd114fbeb..608e78e21 100644 --- a/examples/rllib/stabilizing_highway.py +++ b/examples/rllib/stabilizing_highway.py @@ -83,7 +83,7 @@ # sumo-related parameters (see flow.core.params.SumoParams) sumo=SumoParams( sim_step=0.2, - sumo_binary="sumo-gui", + sumo_binary="sumo", ), # environment related parameters (see flow.core.params.EnvParams) diff --git a/examples/rllib/velocity_bottleneck.py b/examples/rllib/velocity_bottleneck.py index 83167ed14..0e7d265f9 100644 --- a/examples/rllib/velocity_bottleneck.py +++ b/examples/rllib/velocity_bottleneck.py @@ -60,7 +60,8 @@ "reset_inflow": False, "lane_change_duration": 5, "max_accel": 3, - "max_decel": 3 + "max_decel": 3, + "inflow_range": [1000, 2000] } # flow rate diff --git a/examples/sumo/bay_bridge_toll.py b/examples/sumo/bay_bridge_toll.py index 006ce0051..c632834b1 100644 --- a/examples/sumo/bay_bridge_toll.py +++ b/examples/sumo/bay_bridge_toll.py @@ -21,12 +21,14 @@ def bay_bridge_bottleneck_example(sumo_binary=None, Performs a non-RL simulation of the bottleneck portion of the Oakland-San Francisco Bay Bridge. This consists of the toll booth and sections of the road leading up to it. + Parameters ---------- sumo_binary: bool, optional specifies whether to use sumo's gui during execution use_traffic_lights: bool, optional whether to activate the traffic lights in the scenario + Note ---- Unlike the bay_bridge_example, inflows are always activated here. diff --git a/examples/sumo/two_loops_merge_straight.py b/examples/sumo/two_loops_merge_straight.py deleted file mode 100755 index 18946cfd9..000000000 --- a/examples/sumo/two_loops_merge_straight.py +++ /dev/null @@ -1,80 +0,0 @@ -""" -Example of ring road with larger merging ring. -""" - -from flow.controllers import IDMController, SumoLaneChangeController, \ - ContinuousRouter -from flow.core.experiment import SumoExperiment -from flow.core.params import SumoParams, EnvParams, InitialConfig, NetParams, \ - SumoCarFollowingParams, SumoLaneChangeParams -from flow.core.vehicles import Vehicles -from flow.envs.loop.loop_accel import AccelEnv, ADDITIONAL_ENV_PARAMS -from flow.scenarios.loop_merge.scenario import \ - TwoLoopsOneMergingScenario, ADDITIONAL_NET_PARAMS -from flow.scenarios.loop_merge.gen import TwoLoopOneMergingGenerator - - -def two_loops_merge_straight_example(sumo_binary=None): - sumo_params = SumoParams(sim_step=0.1, emission_path="./data/", - sumo_binary="sumo-gui") - - if sumo_binary is not None: - sumo_params.sumo_binary = sumo_binary - - # note that the vehicles are added sequentially by the generator, - # so place the merging vehicles after the vehicles in the ring - vehicles = Vehicles() - vehicles.add(veh_id="idm", - acceleration_controller=(IDMController, {}), - lane_change_controller=(SumoLaneChangeController, {}), - routing_controller=(ContinuousRouter, {}), - num_vehicles=7, - sumo_car_following_params=SumoCarFollowingParams( - minGap=0.0, tau=0.5), - sumo_lc_params=SumoLaneChangeParams()) - vehicles.add(veh_id="merge-idm", - acceleration_controller=(IDMController, {}), - lane_change_controller=(SumoLaneChangeController, {}), - routing_controller=(ContinuousRouter, {}), - num_vehicles=10, - sumo_car_following_params=SumoCarFollowingParams( - minGap=0.01, tau=0.5), - sumo_lc_params=SumoLaneChangeParams()) - - env_params = EnvParams(additional_params=ADDITIONAL_ENV_PARAMS) - - additional_net_params = ADDITIONAL_NET_PARAMS.copy() - additional_net_params["ring_radius"] = 50 - additional_net_params["inner_lanes"] = 1 - additional_net_params["outer_lanes"] = 1 - additional_net_params["lane_length"] = 75 - net_params = NetParams( - no_internal_links=False, - additional_params=additional_net_params - ) - - initial_config = InitialConfig( - x0=50, - spacing="uniform", - additional_params={"merge_bunching": 0} - ) - - scenario = TwoLoopsOneMergingScenario( - name="two-loop-one-merging", - generator_class=TwoLoopOneMergingGenerator, - vehicles=vehicles, - net_params=net_params, - initial_config=initial_config - ) - - env = AccelEnv(env_params, sumo_params, scenario) - - return SumoExperiment(env, scenario) - - -if __name__ == "__main__": - # import the experiment variable - exp = two_loops_merge_straight_example() - - # run for a set number of rollouts / time steps - exp.run(1, 1500, convert_to_csv=True) diff --git a/flow/envs/__init__.py b/flow/envs/__init__.py index 31e748642..96de0f63e 100755 --- a/flow/envs/__init__.py +++ b/flow/envs/__init__.py @@ -7,7 +7,7 @@ from flow.envs.loop.lane_changing import LaneChangeAccelEnv, \ LaneChangeAccelPOEnv from flow.envs.loop.loop_accel import AccelEnv -from flow.envs.loop.loop_merges import TwoLoopsMergeEnv +from flow.envs.loop.loop_merges import TwoLoopsMergePOEnv from flow.envs.loop.wave_attenuation import WaveAttenuationEnv, \ WaveAttenuationPOEnv from flow.envs.merge import WaveAttenuationMergePOEnv @@ -15,7 +15,7 @@ __all__ = ["Env", "AccelEnv", "LaneChangeAccelEnv", "LaneChangeAccelPOEnv", "GreenWaveTestEnv", "GreenWaveTestEnv", "WaveAttenuationMergePOEnv", - "TwoLoopsMergeEnv", "BottleneckEnv", "BottleNeckAccelEnv", + "TwoLoopsMergePOEnv", "BottleneckEnv", "BottleNeckAccelEnv", "WaveAttenuationEnv", "WaveAttenuationPOEnv", "TrafficLightGridEnv", "PO_TrafficLightGridEnv", "DesiredVelocityEnv", "TestEnv", "BayBridgeEnv"] diff --git a/flow/envs/loop/loop_merges.py b/flow/envs/loop/loop_merges.py index f34b4c3ff..0821efc9b 100755 --- a/flow/envs/loop/loop_merges.py +++ b/flow/envs/loop/loop_merges.py @@ -22,7 +22,7 @@ } -class TwoLoopsMergeEnv(Env): +class TwoLoopsMergePOEnv(Env): """Environment for training cooperative merging behavior in a closed loop merge scenario. diff --git a/tests/fast_tests/test_examples.py b/tests/fast_tests/test_examples.py index c6465c6de..22c6e9eb7 100644 --- a/tests/fast_tests/test_examples.py +++ b/tests/fast_tests/test_examples.py @@ -3,8 +3,7 @@ from examples.sumo.figure_eight import figure_eight_example from examples.sumo.highway import highway_example from examples.sumo.sugiyama import sugiyama_example -from examples.sumo.two_loops_merge_straight import \ - two_loops_merge_straight_example +from examples.sumo.loop_merge import loop_merge_example from examples.sumo.grid import grid_example from examples.sumo.bottleneck import bottleneck_example from examples.sumo.merge import merge_example @@ -80,12 +79,12 @@ def test_sugiyama(self): # run the experiment for a few time steps to ensure it doesn't fail exp.run(1, 5) - def test_two_loops_merge_straight(self): + def test_loop_merge(self): """ Verifies that examples/sumo/two_loops_merge_straight.py is working """ # import the experiment variable from the example - exp = two_loops_merge_straight_example(sumo_binary="sumo") + exp = loop_merge_example(sumo_binary="sumo") # run the experiment for a few time steps to ensure it doesn't fail exp.run(1, 5) From 1191fcd190668f9e71f1c52f700e65d493afa4b6 Mon Sep 17 00:00:00 2001 From: AboudyKreidieh Date: Thu, 9 Aug 2018 23:52:28 -0700 Subject: [PATCH 07/25] test fixed --- tests/fast_tests/test_two_loops_one_merging.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/tests/fast_tests/test_two_loops_one_merging.py b/tests/fast_tests/test_two_loops_one_merging.py index c96b6e26a..10d5a73d9 100644 --- a/tests/fast_tests/test_two_loops_one_merging.py +++ b/tests/fast_tests/test_two_loops_one_merging.py @@ -5,7 +5,8 @@ from flow.core.experiment import SumoExperiment from flow.core.params import SumoParams, EnvParams, InitialConfig, NetParams from flow.core.vehicles import Vehicles -from flow.envs.loop.loop_merges import TwoLoopsMergeEnv, ADDITIONAL_ENV_PARAMS +from flow.envs.loop.loop_merges import TwoLoopsMergePOEnv, \ + ADDITIONAL_ENV_PARAMS from flow.scenarios.loop_merge.gen import TwoLoopOneMergingGenerator from flow.scenarios.loop_merge.scenario import TwoLoopsOneMergingScenario @@ -53,7 +54,7 @@ def two_loops_one_merging_exp_setup(vehicles=None): "loop-merges", TwoLoopOneMergingGenerator, vehicles, net_params, initial_config=initial_config) - env = TwoLoopsMergeEnv(env_params, sumo_params, scenario) + env = TwoLoopsMergePOEnv(env_params, sumo_params, scenario) return env, scenario From d0fd5cdae8c4f4f6a0c5d2a3d5d9a5b43e1cfd42 Mon Sep 17 00:00:00 2001 From: AboudyKreidieh Date: Thu, 9 Aug 2018 23:53:35 -0700 Subject: [PATCH 08/25] added missing example --- examples/sumo/loop_merge.py | 83 +++++++++++++++++++++++++++++++++++++ 1 file changed, 83 insertions(+) create mode 100755 examples/sumo/loop_merge.py diff --git a/examples/sumo/loop_merge.py b/examples/sumo/loop_merge.py new file mode 100755 index 000000000..4053c9580 --- /dev/null +++ b/examples/sumo/loop_merge.py @@ -0,0 +1,83 @@ +""" +Example of ring road with larger merging ring. +""" + +from flow.controllers import IDMController, SumoLaneChangeController, \ + ContinuousRouter +from flow.core.experiment import SumoExperiment +from flow.core.params import SumoParams, EnvParams, InitialConfig, NetParams, \ + SumoCarFollowingParams, SumoLaneChangeParams +from flow.core.vehicles import Vehicles +from flow.envs.loop.loop_accel import AccelEnv, ADDITIONAL_ENV_PARAMS +from flow.scenarios.loop_merge.scenario import \ + TwoLoopsOneMergingScenario, ADDITIONAL_NET_PARAMS +from flow.scenarios.loop_merge.gen import TwoLoopOneMergingGenerator + + +def loop_merge_example(sumo_binary=None): + sumo_params = SumoParams(sim_step=0.1, + emission_path="./data/", + sumo_binary="sumo-gui") + + if sumo_binary is not None: + sumo_params.sumo_binary = sumo_binary + + # note that the vehicles are added sequentially by the generator, + # so place the merging vehicles after the vehicles in the ring + vehicles = Vehicles() + vehicles.add(veh_id="idm", + acceleration_controller=(IDMController, {}), + lane_change_controller=(SumoLaneChangeController, {}), + routing_controller=(ContinuousRouter, {}), + num_vehicles=7, + speed_mode="no_collide", + sumo_car_following_params=SumoCarFollowingParams( + minGap=0.0, tau=0.5), + sumo_lc_params=SumoLaneChangeParams()) + vehicles.add(veh_id="merge-idm", + acceleration_controller=(IDMController, {}), + lane_change_controller=(SumoLaneChangeController, {}), + routing_controller=(ContinuousRouter, {}), + num_vehicles=10, + speed_mode="no_collide", + sumo_car_following_params=SumoCarFollowingParams( + minGap=0.01, tau=0.5), + sumo_lc_params=SumoLaneChangeParams()) + + env_params = EnvParams(additional_params=ADDITIONAL_ENV_PARAMS) + + additional_net_params = ADDITIONAL_NET_PARAMS.copy() + additional_net_params["ring_radius"] = 50 + additional_net_params["inner_lanes"] = 1 + additional_net_params["outer_lanes"] = 1 + additional_net_params["lane_length"] = 75 + net_params = NetParams( + no_internal_links=False, + additional_params=additional_net_params + ) + + initial_config = InitialConfig( + x0=50, + spacing="uniform", + additional_params={"merge_bunching": 0} + ) + + scenario = TwoLoopsOneMergingScenario( + name="two-loop-one-merging", + generator_class=TwoLoopOneMergingGenerator, + vehicles=vehicles, + net_params=net_params, + initial_config=initial_config + ) + + env = AccelEnv(env_params, sumo_params, scenario) + + return SumoExperiment(env, scenario) + + +if __name__ == "__main__": + # import the experiment variable + exp = loop_merge_example() + + # run for a set number of rollouts / time steps + exp.run(1, 1500, convert_to_csv=True) From a7a6f5f6522a64c2d596d95ba401f6276d690e78 Mon Sep 17 00:00:00 2001 From: AboudyKreidieh Date: Fri, 10 Aug 2018 13:39:46 -0700 Subject: [PATCH 09/25] discrete traffic light env --- flow/core/experiment.py | 2 +- flow/envs/base_env.py | 7 ++-- flow/envs/green_wave_env.py | 47 ++++++++++++++++--------- flow/envs/intersection_env.py | 4 +-- tests/fast_tests/test_traffic_lights.py | 2 +- 5 files changed, 39 insertions(+), 23 deletions(-) diff --git a/flow/core/experiment.py b/flow/core/experiment.py index 35aa33578..2f606f9b4 100755 --- a/flow/core/experiment.py +++ b/flow/core/experiment.py @@ -52,7 +52,7 @@ def run(self, num_runs, num_steps, rl_actions=None, convert_to_csv=False): info_dict = {} if rl_actions is None: def rl_actions(*_): - return [] + return None rets = [] mean_rets = [] diff --git a/flow/envs/base_env.py b/flow/envs/base_env.py index db7d3ecfd..ff43d860d 100755 --- a/flow/envs/base_env.py +++ b/flow/envs/base_env.py @@ -174,7 +174,8 @@ def start_sumo(self): if os.environ.get("TEST_FLAG", 0): # backoff to decrease likelihood of race condition time_stamp = ''.join(str(time.time()).split('.')) - time.sleep(1.0 * int(time_stamp[-6:]) / 1e6) # 1.0 for consistency w/ above + # 1.0 for consistency w/ above + time.sleep(1.0 * int(time_stamp[-6:]) / 1e6) port = sumolib.miscutils.getFreeSocketPort() # command used to start sumo @@ -604,7 +605,7 @@ def additional_command(self): """Additional commands that may be performed by the step method.""" pass - def apply_rl_actions(self, rl_actions=list()): + def apply_rl_actions(self, rl_actions=None): """Specifies the actions to be performed by the rl agent(s). If no actions are provided at any given step, the rl agents default to @@ -616,7 +617,7 @@ def apply_rl_actions(self, rl_actions=list()): list of actions provided by the RL algorithm """ # ignore if no actions are issued - if len(rl_actions) == 0: + if rl_actions is None: return # clip according to the action space requirements diff --git a/flow/envs/green_wave_env.py b/flow/envs/green_wave_env.py index 1eb7cb091..698cd9162 100644 --- a/flow/envs/green_wave_env.py +++ b/flow/envs/green_wave_env.py @@ -1,6 +1,7 @@ import numpy as np import re +from gym.spaces.discrete import Discrete from gym.spaces.box import Box from gym.spaces.tuple_space import Tuple @@ -12,7 +13,9 @@ "switch_time": 2.0, # whether the traffic lights should be actuated by sumo or RL # options are "controlled" and "actuated" - "tl_type": "controlled" + "tl_type": "controlled", + # determines whether the action space is meant to be discrete or continuous + "discrete": False, } @@ -24,6 +27,10 @@ class TrafficLightGridEnv(Env): * switch_time: minimum switch time for each traffic light (in seconds). Earlier RL commands are ignored. + * tl_type: whether the traffic lights should be actuated by sumo or RL + options are "controlled" and "actuated" + * discrete: determines whether the action space is meant to be discrete or + continuous States An observation is the distance of each vehicle to its intersection, a @@ -90,10 +97,16 @@ def __init__(self, env_params, sumo_params, scenario): self.edge_mapping[key].append(i) break + # check whether the action space is meant to be discrete or continuous + self.discrete = env_params.additional_params.get("discrete", False) + @property def action_space(self): - return Box(low=0, high=1, shape=(self.num_traffic_lights,), - dtype=np.float32) + if self.discrete: + return Discrete(2 ** self.num_traffic_lights) + else: + return Box(low=0, high=1, shape=(self.num_traffic_lights,), + dtype=np.float32) @property def observation_space(self): @@ -128,15 +141,17 @@ def get_state(self): return np.array(state) def _apply_rl_actions(self, rl_actions): + # check if the action space is discrete + if self.discrete: + # convert single value to list of 0's and 1's + rl_mask = [int(x) for x in list('{0:0b}'.format(rl_actions))] + rl_mask = [0] * (self.num_traffic_lights - len(rl_mask)) + rl_mask + else: + # convert values less than 0.5 to zero and above to 1. 0's indicate + # that should not switch the direction + rl_mask = rl_actions > 0.5 - if self.env_params.evaluate: - return - - # convert values less than 0.5 to zero and above to 1. 0's indicate - # that should not switch the direction - rl_mask = rl_actions > 0.5 - - for i, action in enumerate(rl_actions): + for i, action in enumerate(rl_mask): # check if our timer has exceeded the yellow phase, meaning it # should switch to red if self.last_change[i, 2] == 0: # currently yellow @@ -152,7 +167,7 @@ def _apply_rl_actions(self, rl_actions): state='rrrGGGrrrGGG', env=self) self.last_change[i, 2] = 1 else: - if rl_mask[i]: + if action: if self.last_change[i, 1] == 0: self.traffic_lights.set_state( node_id='center{}'.format(i), @@ -196,8 +211,8 @@ def get_distance_to_intersection(self, veh_ids): veh_ids: str vehicle identifier - Yields - ------ + Returns + ------- tup 1st element: distance to closest intersection 2nd element: intersection ID (which also specifies which side of @@ -239,8 +254,8 @@ def _convert_edge(self, edges): edges: list or str name of the edge(s) - Yields - ------ + Returns + ------- list or int a number uniquely identifying each edge """ diff --git a/flow/envs/intersection_env.py b/flow/envs/intersection_env.py index d03d63a27..6c9f0fd31 100644 --- a/flow/envs/intersection_env.py +++ b/flow/envs/intersection_env.py @@ -29,8 +29,8 @@ def get_distance_to_intersection(self, veh_ids): veh_ids: str vehicle identifier - Yields - ------ + Returns + ------- tup 1st element: distance to closest intersection 2nd element: intersection ID (which also specifies which side of diff --git a/tests/fast_tests/test_traffic_lights.py b/tests/fast_tests/test_traffic_lights.py index 9e15e76d5..5aa08d0e8 100644 --- a/tests/fast_tests/test_traffic_lights.py +++ b/tests/fast_tests/test_traffic_lights.py @@ -173,7 +173,7 @@ def test_node_mapping(self): self.assertTrue(self.compare_ordering(ordering)) def test_k_closest(self): - self.env.step([]) + self.env.step(None) node_mapping = self.env.scenario.get_node_mapping() # get the node mapping for node center0 From 716eb2acf6c1f4a831b3ae3f766825661c6d011b Mon Sep 17 00:00:00 2001 From: AboudyKreidieh Date: Sun, 12 Aug 2018 18:19:00 -0700 Subject: [PATCH 10/25] tests for methods in utils/rllib --- flow/core/generator.py | 8 +- flow/core/vehicles.py | 2 +- flow/utils/rllib.py | 7 +- tests/fast_tests/test_json.py | 141 --------------------------- tests/fast_tests/test_util.py | 154 ++++++++++++++++++++++++++++++ tests/fast_tests/test_vehicles.py | 5 +- 6 files changed, 166 insertions(+), 151 deletions(-) delete mode 100644 tests/fast_tests/test_json.py diff --git a/flow/core/generator.py b/flow/core/generator.py index 0dab37e4c..4f7ea2f71 100755 --- a/flow/core/generator.py +++ b/flow/core/generator.py @@ -341,10 +341,10 @@ def make_routes(self, scenario, initial_config): routes = makexml("routes", "http://sumo.dlr.de/xsd/routes_file.xsd") # add the types of vehicles to the xml file - for vtype, type_params in vehicles.types: - type_params_str = {key: str(type_params[key]) - for key in type_params} - routes.append(E("vType", id=vtype, **type_params_str)) + for params in vehicles.types: + type_params_str = {key: str(params["type_params"][key]) + for key in params["type_params"]} + routes.append(E("vType", id=params["veh_id"], **type_params_str)) self.vehicle_ids = vehicles.get_ids() diff --git a/flow/core/vehicles.py b/flow/core/vehicles.py index ee1f2dd0b..e1bae8d1e 100755 --- a/flow/core/vehicles.py +++ b/flow/core/vehicles.py @@ -255,7 +255,7 @@ def add(self, # increase the number of unique types of vehicles in the network, and # add the type to the list of types self.num_types += 1 - self.types.append((veh_id, type_params)) + self.types.append({"veh_id": veh_id, "type_params": type_params}) def update(self, vehicle_obs, sim_obs, env): """Updates the vehicle class with data pertaining to the vehicles at diff --git a/flow/utils/rllib.py b/flow/utils/rllib.py index f20175541..82e009d05 100644 --- a/flow/utils/rllib.py +++ b/flow/utils/rllib.py @@ -3,6 +3,7 @@ generation, serialization, and visualization. """ import json +from copy import deepcopy from flow.core.params import SumoLaneChangeParams, SumoCarFollowingParams, \ SumoParams, InitialConfig, EnvParams, NetParams, InFlows @@ -21,7 +22,7 @@ def default(self, obj): if obj not in allowed_types: if isinstance(obj, Vehicles): - res = obj.initial + res = deepcopy(obj.initial) for res_i in res: res_i["acceleration_controller"] = \ (res_i["acceleration_controller"][0].__name__, @@ -33,7 +34,7 @@ def default(self, obj): res_i["routing_controller"] = \ (res_i["routing_controller"][0].__name__, res_i["routing_controller"][1]) - return obj.initial + return res if hasattr(obj, '__name__'): return obj.__name__ else: @@ -115,7 +116,7 @@ def get_flow_params(config): tls = TrafficLights() if "tls" in flow_params: - initial.__dict__ = flow_params["tls"].copy() + tls.__dict__ = flow_params["tls"].copy() flow_params["sumo"] = sumo flow_params["env"] = env diff --git a/tests/fast_tests/test_json.py b/tests/fast_tests/test_json.py deleted file mode 100644 index 17b3470fc..000000000 --- a/tests/fast_tests/test_json.py +++ /dev/null @@ -1,141 +0,0 @@ -""" -Unit tests for JSON file output and reading (used for visualization) -""" - -import unittest - -import json -import os - -import gym - -import ray -import ray.rllib.ppo as ppo - -from flow.core.util import get_flow_params, get_rllib_config -from flow.core.util import NameEncoder, register_env -from flow.core.params import SumoParams, EnvParams, InitialConfig, NetParams -from flow.scenarios.loop.gen import CircleGenerator -from flow.scenarios.loop.loop_scenario import LoopScenario -from flow.controllers.rlcontroller import RLController -from flow.controllers.car_following_models import IDMController -from flow.controllers.routing_controllers import ContinuousRouter -from flow.core.vehicles import Vehicles - -os.environ["TEST_FLAG"] = "True" - - -def make_create_env(flow_env_name, flow_params, version=0, - exp_tag="example", sumo="sumo"): - env_name = flow_env_name + '-v%s' % version - - sumo_params_dict = flow_params['sumo'] - sumo_params_dict['sumo_binary'] = sumo - sumo_params = SumoParams(**sumo_params_dict) - - env_params_dict = flow_params['env'] - env_params = EnvParams(**env_params_dict) - - net_params_dict = flow_params['net'] - net_params = NetParams(**net_params_dict) - - veh_params = flow_params['veh'] - - init_params = flow_params['initial'] - - def create_env(*_): - # note that the vehicles are added sequentially by the generator, - # so place the merging vehicles after the vehicles in the ring - vehicles = Vehicles() - for v_param in veh_params: - vehicles.add(**v_param) - - initial_config = InitialConfig(**init_params) - - scenario = LoopScenario(exp_tag, CircleGenerator, vehicles, net_params, - initial_config=initial_config) - - pass_params = (flow_env_name, sumo_params, vehicles, env_params, - net_params, initial_config, scenario, version) - - register_env(*pass_params) - env = gym.envs.make(env_name) - - return env - - return create_env, env_name - - -class TestJSON(unittest.TestCase): - # def setUp(self): - # # reload modules, required upon repeated ray.init() - - def test_json(self): - """ - Integration test for json export and import workflow - """ - horizon = 500 - - additional_env_params = {"target_velocity": 8, "max-deacc": -1, - "max-acc": 1, "num_steps": horizon} - additional_net_params = {"length": 260, "lanes": 1, "speed_limit": 30, - "resolution": 40} - vehicle_params = [dict(veh_id="rl", num_vehicles=1, - acceleration_controller=(RLController, {}), - routing_controller=(ContinuousRouter, {})), - dict(veh_id="idm", num_vehicles=21, - acceleration_controller=(IDMController, {}), - routing_controller=(ContinuousRouter, {})) - ] - - flow_params = dict( - sumo=dict(sim_step=0.1), - env=dict(additional_params=additional_env_params), - net=dict(no_internal_links=False, - additional_params=additional_net_params), - veh=vehicle_params, - initial=dict(spacing="uniform", bunching=30, min_gap=0) - ) - - flow_env_name = "WaveAttenuationPOEnv" - exp_tag = "stabilizing_the_ring_example" # experiment prefix - - flow_params['flowenv'] = flow_env_name - flow_params['exp_tag'] = exp_tag - flow_params['module'] = "stabilizing_the_ring" # an example - - # Just to make sure an env can be created successfully - # using these current flow_params - _, _ = make_create_env(flow_env_name, flow_params, - version=0, exp_tag=exp_tag) - - config = ppo.DEFAULT_CONFIG.copy() - # save the flow params for replay - flow_json = json.dumps(flow_params, cls=NameEncoder, sort_keys=True, - indent=4) - config['env_config']['flow_params'] = flow_json - - # dump the config so we can fetch it - json_out_file = '~/params.json' - with open(os.path.expanduser(json_out_file), 'w+') as outfile: - json.dump(config, outfile, cls=NameEncoder, sort_keys=True, - indent=4) - - config = get_rllib_config(os.path.expanduser('~')) - - # Fetching values using utility function `get_flow_params` - imported_flow_params, mce = \ - get_flow_params(config) - - # Making sure the imported flow_params match the originals - self.assertTrue(imported_flow_params == flow_params) - - # delete the created file - os.remove(os.path.expanduser('~/params.json')) - - def tearDown(self): - ray.worker.cleanup() - - -if __name__ == '__main__': - unittest.main() diff --git a/tests/fast_tests/test_util.py b/tests/fast_tests/test_util.py index 4fc4405a3..9f3a6f591 100644 --- a/tests/fast_tests/test_util.py +++ b/tests/fast_tests/test_util.py @@ -1,9 +1,17 @@ import unittest import csv import os +import json +import collections +from flow.core.vehicles import Vehicles +from flow.core.traffic_lights import TrafficLights +from flow.controllers import IDMController, ContinuousRouter, RLController +from flow.core.params import SumoParams, EnvParams, NetParams, InitialConfig from flow.core.util import emission_to_csv from flow.utils.warnings import deprecation_warning +from flow.utils.registry import make_create_env +from flow.utils.rllib import FlowParamsEncoder, get_flow_params os.environ["TEST_FLAG"] = "True" @@ -68,5 +76,151 @@ class Foo(object): deprecation_warning, Foo(), dep_from, dep_to) +class TestRegistry(unittest.TestCase): + + """Tests the methods located in flow/utils/registry.py""" + + def test_make_create_env(self): + """blank.""" + pass + + +class TestRllib(unittest.TestCase): + + """Tests the methods located in flow/utils/rllib.py""" + + def test_encoder_and_get_flow_params(self): + """Tests both FlowParamsEncoder and get_flow_params. + + FlowParamsEncoder is used to serialize the data from a flow_params dict + for replay by the visualizer later. Then, the get_flow_params method is + used to try and read the parameters from the config file, and is + checked to match expected results. + """ + # use a flow_params dict derived from flow/benchmarks/figureeight0.py + vehicles = Vehicles() + vehicles.add(veh_id="human", + acceleration_controller=(IDMController, {"noise": 0.2}), + routing_controller=(ContinuousRouter, {}), + speed_mode="no_collide", + num_vehicles=13) + vehicles.add(veh_id="rl", + acceleration_controller=(RLController, {}), + routing_controller=(ContinuousRouter, {}), + speed_mode="no_collide", + num_vehicles=1) + + flow_params = dict( + exp_tag="figure_eight_0", + env_name="AccelEnv", + scenario="Figure8Scenario", + generator="Figure8Generator", + sumo=SumoParams( + sim_step=0.1, + sumo_binary="sumo", + ), + env=EnvParams( + horizon=1500, + additional_params={ + "target_velocity": 20, + "max_accel": 3, + "max_decel": 3, + }, + ), + net=NetParams( + no_internal_links=False, + additional_params={ + "radius_ring": 30, + "lanes": 1, + "speed_limit": 30, + "resolution": 40, + }, + ), + veh=vehicles, + initial=InitialConfig(), + tls=TrafficLights(), + ) + + # create an config dict with space for the flow_params dict + config = {"env_config": {}} + + # save the flow params for replay + flow_json = json.dumps(flow_params, cls=FlowParamsEncoder, + sort_keys=True, indent=4) + config['env_config']['flow_params'] = flow_json + + # dump the config so we can fetch it + json_out_file = 'params.json' + with open(os.path.expanduser(json_out_file), 'w+') as outfile: + json.dump(config, outfile, cls=FlowParamsEncoder, + sort_keys=True, indent=4) + + # fetch values using utility function `get_flow_params` + imported_flow_params = get_flow_params(config) + + # delete the created file + os.remove(os.path.expanduser('params.json')) + + # TODO(ak): deal with this hack + imported_flow_params["initial"].positions = None + imported_flow_params["initial"].lanes = None + imported_flow_params["net"].in_flows = None + + # make sure the imported flow_params match the originals + self.assertTrue(imported_flow_params["env"].__dict__ == + flow_params["env"].__dict__) + self.assertTrue(imported_flow_params["initial"].__dict__ == + flow_params["initial"].__dict__) + self.assertTrue(imported_flow_params["tls"].__dict__ == + flow_params["tls"].__dict__) + self.assertTrue(imported_flow_params["sumo"].__dict__ == + flow_params["sumo"].__dict__) + self.assertTrue(imported_flow_params["net"].__dict__ == + flow_params["net"].__dict__) + + self.assertTrue(imported_flow_params["exp_tag"] == + flow_params["exp_tag"]) + self.assertTrue(imported_flow_params["env_name"] == + flow_params["env_name"]) + self.assertTrue(imported_flow_params["scenario"] == + flow_params["scenario"]) + self.assertTrue(imported_flow_params["generator"] == + flow_params["generator"]) + + def search_dicts(obj1, obj2): + """Searches through dictionaries as well as lists of dictionaries + recursively to determine if any two components are mismatched.""" + for key in obj1.keys(): + # if an next element is a list, either compare the two lists, + # or if the lists contain dictionaries themselves, look at each + # dictionary component recursively to check for mismatches + if isinstance(obj1[key], list): + if len(obj1[key]) > 0: + if isinstance(obj1[key][0], dict): + for i in range(len(obj1[key])): + if not search_dicts(obj1[key][i], obj2[key][i]): + return False + elif obj1[key] != obj2[key]: + return False + # if the next element is a dict, run through it recursively to + # determine if the separate elements of the dict match + if isinstance(obj1[key], (dict, collections.OrderedDict)): + if not search_dicts(obj1[key], obj2[key]): + return False + # if it is neither a list or a dictionary, compare to determine + # if the two elements match + elif obj1[key] != obj2[key]: + # if the two elements that are being compared are objects, + # make sure that they are the same type + if not isinstance(obj1[key], type(obj2[key])): + return False + return True + + # make sure that the Vehicles class that was imported matches the + # original one + if not search_dicts(imported_flow_params["veh"].__dict__, + flow_params["veh"].__dict__): + raise AssertionError + if __name__ == '__main__': unittest.main() diff --git a/tests/fast_tests/test_vehicles.py b/tests/fast_tests/test_vehicles.py index f7b356bb0..ffe25dd18 100644 --- a/tests/fast_tests/test_vehicles.py +++ b/tests/fast_tests/test_vehicles.py @@ -60,7 +60,7 @@ def test_controlled_id_params(self): acceleration_controller=(IDMController, {}), speed_mode='no_collide', lane_change_mode="no_lat_collide") - self.assertEqual(vehicles.types[0][1]["minGap"], 0) + self.assertEqual(vehicles.types[0]["type_params"]["minGap"], 0) # check that, if the vehicle is a SumoCarFollowingController vehicle, # then its minGap, accel, and decel are set to default @@ -70,7 +70,8 @@ def test_controlled_id_params(self): speed_mode='no_collide', lane_change_mode="no_lat_collide") default_mingap = SumoCarFollowingParams().controller_params["minGap"] - self.assertEqual(vehicles.types[0][1]["minGap"], default_mingap) + self.assertEqual(vehicles.types[0]["type_params"]["minGap"], + default_mingap) def test_add_vehicles_human(self): """ From c9b050b77b0bb8fa23eab7503681971315772122 Mon Sep 17 00:00:00 2001 From: AboudyKreidieh Date: Sun, 12 Aug 2018 18:36:55 -0700 Subject: [PATCH 11/25] added test for utils/registry.py --- tests/fast_tests/test_util.py | 88 ++++++++++++++++++++++++++++++++++- 1 file changed, 86 insertions(+), 2 deletions(-) diff --git a/tests/fast_tests/test_util.py b/tests/fast_tests/test_util.py index 9f3a6f591..000e71b1f 100644 --- a/tests/fast_tests/test_util.py +++ b/tests/fast_tests/test_util.py @@ -81,8 +81,92 @@ class TestRegistry(unittest.TestCase): """Tests the methods located in flow/utils/registry.py""" def test_make_create_env(self): - """blank.""" - pass + """Tests that the make_create_env methods generates an environment with + the expected flow parameters.""" + # use a flow_params dict derived from flow/benchmarks/figureeight0.py + vehicles = Vehicles() + vehicles.add(veh_id="human", + acceleration_controller=(IDMController, {"noise": 0.2}), + routing_controller=(ContinuousRouter, {}), + speed_mode="no_collide", + num_vehicles=13) + vehicles.add(veh_id="rl", + acceleration_controller=(RLController, {}), + routing_controller=(ContinuousRouter, {}), + speed_mode="no_collide", + num_vehicles=1) + + flow_params = dict( + exp_tag="figure_eight_0", + env_name="AccelEnv", + scenario="Figure8Scenario", + generator="Figure8Generator", + sumo=SumoParams( + sim_step=0.1, + sumo_binary="sumo", + ), + env=EnvParams( + horizon=1500, + additional_params={ + "target_velocity": 20, + "max_accel": 3, + "max_decel": 3, + }, + ), + net=NetParams( + no_internal_links=False, + additional_params={ + "radius_ring": 30, + "lanes": 1, + "speed_limit": 30, + "resolution": 40, + }, + ), + veh=vehicles, + initial=InitialConfig(), + tls=TrafficLights(), + ) + + # some random version number for testing + v = 23434 + + # call make_create_env + create_env, env_name = make_create_env(params=flow_params, version=v) + + # check that the name is correct + self.assertEqual(env_name, '{}-v{}'.format(flow_params["env_name"], v)) + + # create the gym environment + env = create_env() + + # Note that we expect the port number is sumo_params to change, and + # that this feature is in fact needed to avoid race conditions + flow_params["sumo"].port = env.env.sumo_params.port + + # TODO(ak): deal with this hack + flow_params["initial"].positions = \ + env.env.scenario.initial_config.positions + flow_params["initial"].lanes = env.env.scenario.initial_config.lanes + + # check that each of the parameter match + self.assertEqual(env.env.env_params.__dict__, + flow_params["env"].__dict__) + self.assertEqual(env.env.sumo_params.__dict__, + flow_params["sumo"].__dict__) + self.assertEqual(env.env.traffic_lights.__dict__, + flow_params["tls"].__dict__) + self.assertEqual(env.env.scenario.net_params.__dict__, + flow_params["net"].__dict__) + self.assertEqual(env.env.scenario.net_params.__dict__, + flow_params["net"].__dict__) + self.assertEqual(env.env.scenario.initial_config.__dict__, + flow_params["initial"].__dict__) + self.assertEqual(env.env.__class__.__name__, + flow_params["env_name"]) + self.assertEqual(env.env.scenario.__class__.__name__, + flow_params["scenario"]) + self.assertEqual(env.env.scenario.generator_class.__name__, + flow_params["generator"]) class TestRllib(unittest.TestCase): From 8cadd7637b8aad956074170c97b69212d98c81ea Mon Sep 17 00:00:00 2001 From: AboudyKreidieh Date: Sun, 12 Aug 2018 18:49:07 -0700 Subject: [PATCH 12/25] pep8 --- tests/fast_tests/test_util.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/tests/fast_tests/test_util.py b/tests/fast_tests/test_util.py index 000e71b1f..7fd8b4ecf 100644 --- a/tests/fast_tests/test_util.py +++ b/tests/fast_tests/test_util.py @@ -282,7 +282,8 @@ def search_dicts(obj1, obj2): if len(obj1[key]) > 0: if isinstance(obj1[key][0], dict): for i in range(len(obj1[key])): - if not search_dicts(obj1[key][i], obj2[key][i]): + if not search_dicts(obj1[key][i], + obj2[key][i]): return False elif obj1[key] != obj2[key]: return False @@ -306,5 +307,6 @@ def search_dicts(obj1, obj2): flow_params["veh"].__dict__): raise AssertionError + if __name__ == '__main__': unittest.main() From 217bf74e405b37110aabd50ed22db219b47f6c49 Mon Sep 17 00:00:00 2001 From: AboudyKreidieh Date: Mon, 13 Aug 2018 00:57:20 -0700 Subject: [PATCH 13/25] removed a file from the front page of flow that I don't think is used by anyone --- pre-commit.sh | 16 ---------------- 1 file changed, 16 deletions(-) delete mode 100755 pre-commit.sh diff --git a/pre-commit.sh b/pre-commit.sh deleted file mode 100755 index 8f18f8744..000000000 --- a/pre-commit.sh +++ /dev/null @@ -1,16 +0,0 @@ -#!/usr/bin/env bash - -# pre-commit.sh - -git stash -q --keep-index - -# Test prospective commit -pushd flow_dev -python -m unittest discover tests/fast -RESULT=$? -popd - -git stash pop -q - -[ $RESULT -ne 0 ] && exit 1 -exit 0 From 6eda62141d2f682a6c042f9321df443609cfb601 Mon Sep 17 00:00:00 2001 From: nskh Date: Wed, 15 Aug 2018 15:22:50 -0700 Subject: [PATCH 14/25] fixing typo (rllab->rllib) --- docs/source/flow_setup.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/source/flow_setup.rst b/docs/source/flow_setup.rst index 823078ba4..3bb37f29f 100644 --- a/docs/source/flow_setup.rst +++ b/docs/source/flow_setup.rst @@ -172,7 +172,7 @@ See `getting started with RLlib Date: Wed, 15 Aug 2018 15:34:48 -0700 Subject: [PATCH 15/25] PR fix --- flow/envs/loop/loop_merges.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/flow/envs/loop/loop_merges.py b/flow/envs/loop/loop_merges.py index 0821efc9b..5a98196ae 100755 --- a/flow/envs/loop/loop_merges.py +++ b/flow/envs/loop/loop_merges.py @@ -23,8 +23,8 @@ class TwoLoopsMergePOEnv(Env): - """Environment for training cooperative merging behavior in a closed loop - merge scenario. + """Environment for training cooperative merging behavior in a partially + observable closed loop merge scenario. WARNING: only supports 1 RL vehicle From c8912c7d26dcd2ea0472805018502a4476d6dddd Mon Sep 17 00:00:00 2001 From: eugenevinitsky Date: Thu, 16 Aug 2018 09:57:00 -0700 Subject: [PATCH 16/25] minor pep8 fixes --- flow/core/rewards.py | 12 ++++++------ flow/envs/base_env.py | 2 +- flow/version.py | 2 +- tests/fast_tests/test_experiment_base_class.py | 2 +- 4 files changed, 9 insertions(+), 9 deletions(-) diff --git a/flow/core/rewards.py b/flow/core/rewards.py index 664d0e3c8..27e3eb67c 100755 --- a/flow/core/rewards.py +++ b/flow/core/rewards.py @@ -35,11 +35,11 @@ def desired_velocity(env, fail=False): if any(vel < -100) or fail: return 0. - max_cost = np.array([env.env_params.additional_params["target_velocity"]] * - num_vehicles) + target_vel = env.env_params.additional_params["target_velocity"] + max_cost = np.array([target_vel] * num_vehicles) max_cost = np.linalg.norm(max_cost) - cost = vel - env.env_params.additional_params["target_velocity"] + cost = vel - target_vel cost = np.linalg.norm(cost) return max(max_cost - cost, 0) / max_cost @@ -69,11 +69,11 @@ def max_edge_velocity(env, edge_list, fail=False): if any(vel < -100) or fail: return 0. - max_cost = np.array([env.env_params.additional_params["target_velocity"]] * - num_vehicles) + target_vel = env.env_params.additional_params["target_velocity"] + max_cost = np.array([target_vel] * num_vehicles) max_cost = np.linalg.norm(max_cost) - cost = vel - env.env_params.additional_params["target_velocity"] + cost = vel - target_vel cost = np.linalg.norm(cost) return max(max_cost - cost, 0) diff --git a/flow/envs/base_env.py b/flow/envs/base_env.py index db7d3ecfd..6f6ea01c6 100755 --- a/flow/envs/base_env.py +++ b/flow/envs/base_env.py @@ -174,7 +174,7 @@ def start_sumo(self): if os.environ.get("TEST_FLAG", 0): # backoff to decrease likelihood of race condition time_stamp = ''.join(str(time.time()).split('.')) - time.sleep(1.0 * int(time_stamp[-6:]) / 1e6) # 1.0 for consistency w/ above + time.sleep(1.0 * int(time_stamp[-6:]) / 1e6) port = sumolib.miscutils.getFreeSocketPort() # command used to start sumo diff --git a/flow/version.py b/flow/version.py index 40692a7a9..3dc1f76bc 100644 --- a/flow/version.py +++ b/flow/version.py @@ -1 +1 @@ -__version__="0.1.0" +__version__ = "0.1.0" diff --git a/tests/fast_tests/test_experiment_base_class.py b/tests/fast_tests/test_experiment_base_class.py index 599018ac5..b0e4d6262 100644 --- a/tests/fast_tests/test_experiment_base_class.py +++ b/tests/fast_tests/test_experiment_base_class.py @@ -3,7 +3,7 @@ from flow.core.experiment import SumoExperiment from flow.core.vehicles import Vehicles -from flow.controllers import IDMController, RLController, ContinuousRouter +from flow.controllers import RLController, ContinuousRouter from tests.setup_scripts import ring_road_exp_setup import numpy as np From e33916f6534503668a1b5da3e878d5d6b4215a97 Mon Sep 17 00:00:00 2001 From: AboudyKreidieh Date: Thu, 16 Aug 2018 10:39:28 -0700 Subject: [PATCH 17/25] test includes inflows now --- tests/fast_tests/test_util.py | 60 ++++++++++++++++++++++++----------- 1 file changed, 41 insertions(+), 19 deletions(-) diff --git a/tests/fast_tests/test_util.py b/tests/fast_tests/test_util.py index 7fd8b4ecf..d0fa815ae 100644 --- a/tests/fast_tests/test_util.py +++ b/tests/fast_tests/test_util.py @@ -7,7 +7,8 @@ from flow.core.vehicles import Vehicles from flow.core.traffic_lights import TrafficLights from flow.controllers import IDMController, ContinuousRouter, RLController -from flow.core.params import SumoParams, EnvParams, NetParams, InitialConfig +from flow.core.params import SumoParams, EnvParams, NetParams, InitialConfig, \ + InFlows from flow.core.util import emission_to_csv from flow.utils.warnings import deprecation_warning from flow.utils.registry import make_create_env @@ -181,43 +182,58 @@ def test_encoder_and_get_flow_params(self): used to try and read the parameters from the config file, and is checked to match expected results. """ - # use a flow_params dict derived from flow/benchmarks/figureeight0.py + # use a flow_params dict derived from flow/benchmarks/merge0.py vehicles = Vehicles() vehicles.add(veh_id="human", - acceleration_controller=(IDMController, {"noise": 0.2}), - routing_controller=(ContinuousRouter, {}), + acceleration_controller=(IDMController, {}), speed_mode="no_collide", - num_vehicles=13) + num_vehicles=5) vehicles.add(veh_id="rl", acceleration_controller=(RLController, {}), - routing_controller=(ContinuousRouter, {}), speed_mode="no_collide", - num_vehicles=1) + num_vehicles=0) + + inflow = InFlows() + inflow.add(veh_type="human", edge="inflow_highway", + vehs_per_hour=1800, + departLane="free", departSpeed=10) + inflow.add(veh_type="rl", edge="inflow_highway", + vehs_per_hour=200, + departLane="free", departSpeed=10) + inflow.add(veh_type="human", edge="inflow_merge", vehs_per_hour=100, + departLane="free", departSpeed=7.5) flow_params = dict( - exp_tag="figure_eight_0", - env_name="AccelEnv", - scenario="Figure8Scenario", - generator="Figure8Generator", + exp_tag="merge_0", + env_name="WaveAttenuationMergePOEnv", + scenario="MergeScenario", + generator="MergeGenerator", sumo=SumoParams( - sim_step=0.1, + restart_instance=True, + sim_step=0.5, sumo_binary="sumo", ), env=EnvParams( - horizon=1500, + horizon=750, + sims_per_step=2, + warmup_steps=0, additional_params={ + "max_accel": 1.5, + "max_decel": 1.5, "target_velocity": 20, - "max_accel": 3, - "max_decel": 3, + "num_rl": 5, }, ), net=NetParams( + in_flows=inflow, no_internal_links=False, additional_params={ - "radius_ring": 30, - "lanes": 1, + "merge_length": 100, + "pre_merge_length": 500, + "post_merge_length": 100, + "merge_lanes": 1, + "highway_lanes": 1, "speed_limit": 30, - "resolution": 40, }, ), veh=vehicles, @@ -248,9 +264,15 @@ def test_encoder_and_get_flow_params(self): # TODO(ak): deal with this hack imported_flow_params["initial"].positions = None imported_flow_params["initial"].lanes = None + + # test that this inflows are correct + self.assertTrue(imported_flow_params["net"].in_flows.__dict__ == + flow_params["net"].in_flows.__dict__) + imported_flow_params["net"].in_flows = None + flow_params["net"].in_flows = None - # make sure the imported flow_params match the originals + # make sure the rest of the imported flow_params match the originals self.assertTrue(imported_flow_params["env"].__dict__ == flow_params["env"].__dict__) self.assertTrue(imported_flow_params["initial"].__dict__ == From 7b5b36b25203e51e201f4c7dfaa5c93a05a997da Mon Sep 17 00:00:00 2001 From: AboudyKreidieh Date: Thu, 16 Aug 2018 10:42:08 -0700 Subject: [PATCH 18/25] typo --- tests/fast_tests/test_util.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/fast_tests/test_util.py b/tests/fast_tests/test_util.py index d0fa815ae..74159bf0b 100644 --- a/tests/fast_tests/test_util.py +++ b/tests/fast_tests/test_util.py @@ -140,7 +140,7 @@ def test_make_create_env(self): # create the gym environment env = create_env() - # Note that we expect the port number is sumo_params to change, and + # Note that we expect the port number in sumo_params to change, and # that this feature is in fact needed to avoid race conditions flow_params["sumo"].port = env.env.sumo_params.port From 9ff877d4678b1fee442b7601ac37663882db1c75 Mon Sep 17 00:00:00 2001 From: Nishant Date: Mon, 20 Aug 2018 18:16:49 -0700 Subject: [PATCH 19/25] draft tutorial --- tutorials/tutorial11_rllab_ec2.ipynb | 98 ++++++++-------------------- 1 file changed, 28 insertions(+), 70 deletions(-) diff --git a/tutorials/tutorial11_rllab_ec2.ipynb b/tutorials/tutorial11_rllab_ec2.ipynb index 9b29ca077..3d12ec558 100644 --- a/tutorials/tutorial11_rllab_ec2.ipynb +++ b/tutorials/tutorial11_rllab_ec2.ipynb @@ -13,94 +13,48 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "First, follow the [rllab cluster setup instructions](https://rllab.readthedocs.io/en/latest/user/cluster.html) with region `us-west-1`. Modify `rllab/config_personal.py` to reference the most currently Flow Docker image (at the time of this writing, `evinitsky/flow`). \n", + "## Setting up rllab with AWS\n", + " \n", + "First, follow the [rllab cluster setup instructions](https://rllab.readthedocs.io/en/latest/user/cluster.html) with region `us-west-1`. Modify `rllab/config_personal.py` to reference the most current Flow Docker image (at the time of this writing, `evinitsky/flow`). [@fangyu is this true?]\n", "\n", - "Navigate to your `flow-devel` directory and modify `Makefile.template` per the instructions in that file. \n", - "\n", - "- The variable `RLLABDIR` should be the relative path from your `flow-devel` directory to \n", - "- " + "Navigate to your `flow` directory and modify `Makefile.template` per the instructions in that file. The variable `RLLABDIR` should be the relative path from your `flow` directory to `rllab` and should not have a backslash at the end. " ] }, { - "cell_type": "code", - "execution_count": null, + "cell_type": "markdown", "metadata": { "collapsed": true }, - "outputs": [], - "source": [] - }, - { - "cell_type": "markdown", - "metadata": {}, "source": [ - "# Setting up AWS\n", + "## Running an experiment\n", + "\n", + "When running AWS experiments, your entire `rllab` directory is uploaded to AWS so that the files necessary for your experiment are available to the EC2 instance. Thus, commands are included to copy over your `flow` directory to your `rllab` root directory (this is the reason for the `RLLABDIR` variable above). \n", "\n", + "- Before running an experiment, run `make prepare` from your `flow` directory.\n", + "- Ensure you have committed or otherwise tracked the state of your `flow` directory, because that instance is what will be used to run your experiment. Upon visualization, the same files will need to be used—for example, changes to environment's state-space would break the ability to run a trained policy using a different state space. Check out an old commit of your `flow` directory and run `make prepare` to use visualization tools included with rllab.\n", "\n", - " - Pull `openai/rllab-distributed` repository and switch to production `sharedPolicyUpdate_release` branch\n", - " ```bash\n", - " git clone https://github.com/openai/rllab-distributed.git\n", - " cd rllab-distributed\n", - " git checkout sharedPolicyUpdate_release\n", - " ```\n", - " - Follow [rllab local setup instructions](https://rllab.readthedocs.io/en/latest/user/installation.html)\n", - " - Follow [rllab cluster setup instructions](http://rllab.readthedocs.io/en/latest/user/cluster.html)\n", - " - If prompted, region = us-west-1\n", - " - Note: the current Docker image path is \"evinitsky/flow-distributed\". Your `rllab-distributed/rllab/config_personal.py` should reflect that.\n", - " - (Optional): As desired, add to `config_personal.py` files and \n", - " directories that you do not need uploaded to EC2 for every \n", - " experiment by modifying `FAST_CODE_SYNC_IGNORES`.\n", - " - Go to `Makefile.template` in `learning-traffic/flow_dev` and update\n", - " the path to your rllab root directory (no trailing slash)\n", - " - The `flow_dev` reference in the Makefile might need to be updated to `flow`\n", - " - (See note below); Run `make prepare` \n", - " - Try an example! Run any experiment from `flow_dev/examples`, change\n", - " mode to “ec2”\n", - " - You can run it locally by changing the mode to local_docker. If this isn't working, make sure to check that your local docker image is the most current image. \n", - " - Log into AWS via: https://cathywu.signin.aws.amazon.com/console\n", - " - If you don’t see the instance you just launched (give it a few \n", - " minutes) running on AWS, then make sure your region is correct (go to\n", - " top right and change to `US West (N. California)` \n", + "`make clean` removes the debug directory and also all XML files in rllab root directory to reduce the size of the data to upload to AWS. If you are using already-existing network files (from, say, OpenStreetMap), ensure they do not get deleted by `make clean` by storing such files elsewhere.\n", "\n", - "## Notes\n", + "Inside the experiment, change the `mode` to `ec2` (other options are `local` and `local_docker`). You should run the experiment in `local_docker` mode briefly before running the `ec2` version to ensure there are no errors, particularly with Docker image compatability\n", "\n", - "- When we run experiments on AWS, we create a new instance for each\n", - "seed and use the Docker image I created as the VM. Built into the rllab \n", - "script for running experiments in EC2 mode, we upload the rllab root \n", - "directory to AWS. This way, the AWS instance has access to all files it\n", - " might need to successfully run the experiment. Editing that code is\n", - " pretty complicated, so Cathy and I have decided on the following \n", - " workflow:\n", - " - All code modification will happen in the learning-traffic directory\n", - " - Before each experiment, run the command `make prepare` , which will\n", - " remove the flow_dev directory in rllab root and copy\n", - " `learning-traffic/flow_dev-dev/flow_dev` into your rllab root directory\n", - " - This means if you make modifications to flow_dev in the rllab\n", - " directory, they may be lost\n", - " - Before each experiment, always make sure you have a commit to that \n", - " exact snapshot of the `flow_dev` directory. This is because you may\n", - " modify flow_dev later. When you want to run `visualizer.py` , which is\n", - " our modified version of `sim_policy.py` , AKA when you want to \n", - " create rollout plots, you need the files in `rllab/flow_dev` to match\n", - " the files that were there when you originally ran the experiment.\n", - " So when you want to create rollout plots, you will checkout the\n", - " commit that matches when you ran the experiment and run make \n", - " prepare, then you can create rollout plots in the rllab directory.\n", - " - Ping me if there are issues!\n", - "- I recommend cleaning up your rllab directory, especially if you \n", - "notice you’re uploading a large size to AWS (it will tell you how many\n", - " MB you are uploading, should be < 5 MB). The command `make clean` \n", - " removes the debug directory (since so far we hardcoded that our SUMO\n", - " files go into that directory, this should be changed in the future) \n", - " and also all XML files in rllab root directory.\n" + "After running `python example.py` once the `mode` of `example.py` is `ec2`, you should see your experiment running on AWS." ] }, { - "cell_type": "code", - "execution_count": null, + "cell_type": "markdown", "metadata": { "collapsed": true }, + "source": [ + "## Fetching Results\n", + "\n", + "To get the results of your AWS experiments, navigate to your `rllab` directory and run `python scripts/sync_s3.py`. " + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, "outputs": [], "source": [] } @@ -122,6 +76,10 @@ "nbconvert_exporter": "python", "pygments_lexer": "ipython3", "version": "3.5.2" + }, + "widgets": { + "state": {}, + "version": "1.1.2" } }, "nbformat": 4, From e9f7ea00725f1a171f402720b51b8affa11fdf13 Mon Sep 17 00:00:00 2001 From: Nishant Date: Mon, 20 Aug 2018 18:20:10 -0700 Subject: [PATCH 20/25] result dir --- tutorials/tutorial11_rllab_ec2.ipynb | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/tutorials/tutorial11_rllab_ec2.ipynb b/tutorials/tutorial11_rllab_ec2.ipynb index 3d12ec558..86f61bd5f 100644 --- a/tutorials/tutorial11_rllab_ec2.ipynb +++ b/tutorials/tutorial11_rllab_ec2.ipynb @@ -48,7 +48,8 @@ "source": [ "## Fetching Results\n", "\n", - "To get the results of your AWS experiments, navigate to your `rllab` directory and run `python scripts/sync_s3.py`. " + "- To get the results of your AWS experiments, navigate to your `rllab` directory and run `python scripts/sync_s3.py`. \n", + "- Your experiment results will be in `data/s3` in your `rllab` directory." ] }, { From 5f3ebc20450aa9ced952540bbba11710c1233ec3 Mon Sep 17 00:00:00 2001 From: Nishant Date: Fri, 24 Aug 2018 17:41:49 -0700 Subject: [PATCH 21/25] deleting cell --- tutorials/tutorial11_rllab_ec2.ipynb | 7 ------- 1 file changed, 7 deletions(-) diff --git a/tutorials/tutorial11_rllab_ec2.ipynb b/tutorials/tutorial11_rllab_ec2.ipynb index 86f61bd5f..dc31385ed 100644 --- a/tutorials/tutorial11_rllab_ec2.ipynb +++ b/tutorials/tutorial11_rllab_ec2.ipynb @@ -51,13 +51,6 @@ "- To get the results of your AWS experiments, navigate to your `rllab` directory and run `python scripts/sync_s3.py`. \n", "- Your experiment results will be in `data/s3` in your `rllab` directory." ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] } ], "metadata": { From 0328d1cd2d875cbe4a7e97c21f42b2e1ff912375 Mon Sep 17 00:00:00 2001 From: Nishant Date: Fri, 24 Aug 2018 22:48:28 -0700 Subject: [PATCH 22/25] extra --- flow/envs/base_env.py | 6 ------ flow/utils/warnings.py | 17 ----------------- setup.py | 1 - 3 files changed, 24 deletions(-) delete mode 100644 flow/utils/warnings.py diff --git a/flow/envs/base_env.py b/flow/envs/base_env.py index 96089b70f..445f2b1e7 100755 --- a/flow/envs/base_env.py +++ b/flow/envs/base_env.py @@ -890,12 +890,6 @@ def teardown_sumo(self): except Exception: print("Error during teardown: {}".format(traceback.format_exc())) - def teardown_sumo(self): - try: - os.killpg(self.sumo_proc.pid, signal.SIGTERM) - except Exception: - print("Error during teardown: {}".format(traceback.format_exc())) - def _seed(self, seed=None): return [] diff --git a/flow/utils/warnings.py b/flow/utils/warnings.py deleted file mode 100644 index 27b7be18f..000000000 --- a/flow/utils/warnings.py +++ /dev/null @@ -1,17 +0,0 @@ -import warnings - - -def deprecation_warning(obj, dep_from, dep_to): - """Prints a deprecation warning. - - Parameters - ---------- - obj: class - The class with the deprecated attribute - dep_from: str - old (deprecated) name of the attribute - dep_to: str - new name for the attribute - """ - warnings.warn("The attribute {} in {} is deprecated, use {} instead.". - format(dep_from, obj.__class__.__name__, dep_to)) diff --git a/setup.py b/setup.py index d4f2fe20a..7dad6739a 100644 --- a/setup.py +++ b/setup.py @@ -7,7 +7,6 @@ from flow.version import __version__ - def _read_requirements_file(): req_file_path = '%s/requirements.txt' % dirname(realpath(__file__)) with open(req_file_path) as f: From e43e1ed4b1c48829417375f4b626112353e5679f Mon Sep 17 00:00:00 2001 From: Nishant Date: Fri, 24 Aug 2018 23:02:20 -0700 Subject: [PATCH 23/25] added rllab ec2 tutorial to docs --- docs/source/index.rst | 1 + docs/source/rllabec2.rst | 60 ++++++++++++++++++++++++++++++++++++++++ 2 files changed, 61 insertions(+) create mode 100644 docs/source/rllabec2.rst diff --git a/docs/source/index.rst b/docs/source/index.rst index 798727895..3edb5543d 100644 --- a/docs/source/index.rst +++ b/docs/source/index.rst @@ -19,6 +19,7 @@ Flow is a work in progress - input is welcome. Available documentation is limite intro flow_setup Tutorials + rllabec2 visualizing modules diff --git a/docs/source/rllabec2.rst b/docs/source/rllabec2.rst new file mode 100644 index 000000000..ed858616f --- /dev/null +++ b/docs/source/rllabec2.rst @@ -0,0 +1,60 @@ +Running rllab experiments on EC2 +================================ + +This page covers the process of running rllab experients on an Amazon +EC2 instance. This tutorial assumes rllab has been installed correctly +(`instructions `_). + +Setting up rllab with AWS +------------------------- + +First, follow the `rllab cluster setup +instructions `__ +with region ``us-west-1``. Modify ``rllab/config_personal.py`` to +reference the most current Flow Docker image. + +Navigate to your ``flow`` directory and modify ``Makefile.template`` per +the instructions in that file. The variable ``RLLABDIR`` should be the +relative path from your ``flow`` directory to ``rllab`` and should not +have a backslash at the end. + +Running an experiment +--------------------- + +When running AWS experiments, your entire ``rllab`` directory is +uploaded to AWS so that the files necessary for your experiment are +available to the EC2 instance. Thus, commands are included to copy over +your ``flow`` directory to your ``rllab`` root directory (this is the +reason for the ``RLLABDIR`` variable above). + +- Before running an experiment, run ``make prepare`` from your ``flow`` + directory. +- Ensure you have committed or otherwise tracked the state of your + ``flow`` directory, because that instance is what will be used to run + your experiment. Upon visualization, the same files will need to be + used—for example, changes to environment's state-space would break + the ability to run a trained policy using a different state space. + Check out an old commit of your ``flow`` directory and run + ``make prepare`` to use visualization tools included with rllab. + +``make clean`` removes the debug directory and also all XML files in +rllab root directory to reduce the size of the data to upload to AWS. If +you are using already-existing network files (from, say, OpenStreetMap), +ensure they do not get deleted by ``make clean`` by storing such files +elsewhere. + +Inside the experiment, change the ``mode`` to ``ec2`` (other options are +``local`` and ``local_docker``). You should run the experiment in +``local_docker`` mode briefly before running the ``ec2`` version to +ensure there are no errors, particularly with Docker image compatability + +After running ``python example.py`` once the ``mode`` of ``example.py`` +is ``ec2``, you should see your experiment running on AWS. + +Fetching Results +---------------- + +- To get the results of your AWS experiments, navigate to your + ``rllab`` directory and run ``python scripts/sync_s3.py``. +- Your experiment results will be in ``data/s3`` in your ``rllab`` + directory. From 00671ce9640df1e749a32de7a83f8a6ca5ae1483 Mon Sep 17 00:00:00 2001 From: Nishant Kheterpal Date: Sat, 8 Sep 2018 14:19:03 -0700 Subject: [PATCH 24/25] added tutorials substructure to docs --- docs/source/index.rst | 2 +- docs/source/rllabec2.rst | 10 +++++----- docs/source/tutorials.rst | 12 ++++++++++++ 3 files changed, 18 insertions(+), 6 deletions(-) create mode 100644 docs/source/tutorials.rst diff --git a/docs/source/index.rst b/docs/source/index.rst index 1982967a0..4dc8aabc5 100644 --- a/docs/source/index.rst +++ b/docs/source/index.rst @@ -19,7 +19,7 @@ Flow is a work in progress - input is welcome. Available documentation is limite intro flow_setup - Tutorials + tutorials visualizing modules diff --git a/docs/source/rllabec2.rst b/docs/source/rllabec2.rst index ed858616f..af617f1e2 100644 --- a/docs/source/rllabec2.rst +++ b/docs/source/rllabec2.rst @@ -15,8 +15,8 @@ reference the most current Flow Docker image. Navigate to your ``flow`` directory and modify ``Makefile.template`` per the instructions in that file. The variable ``RLLABDIR`` should be the -relative path from your ``flow`` directory to ``rllab`` and should not -have a backslash at the end. +relative path from your ``flow`` directory to ``rllab`` and **should not +have a backslash at the end**. Running an experiment --------------------- @@ -32,10 +32,10 @@ reason for the ``RLLABDIR`` variable above). - Ensure you have committed or otherwise tracked the state of your ``flow`` directory, because that instance is what will be used to run your experiment. Upon visualization, the same files will need to be - used—for example, changes to environment's state-space would break + used—for example, changes to your environment's state-space would break the ability to run a trained policy using a different state space. - Check out an old commit of your ``flow`` directory and run - ``make prepare`` to use visualization tools included with rllab. + Check out an old commit of your ``flow`` directory before visualizing + your experiment results. ``make clean`` removes the debug directory and also all XML files in rllab root directory to reduce the size of the data to upload to AWS. If diff --git a/docs/source/tutorials.rst b/docs/source/tutorials.rst new file mode 100644 index 000000000..ceff392e6 --- /dev/null +++ b/docs/source/tutorials.rst @@ -0,0 +1,12 @@ +Tutorials +========= +Tutorials for learning how to use Flow are available, both on GitHub +and as part of this documentation. + + +.. toctree:: + :maxdepth: 1 + :caption: Links: + + rllabec2 + GitHub Tutorials \ No newline at end of file From ef93f5966e42a51fdaed2fcd6f416ebd8f907c8a Mon Sep 17 00:00:00 2001 From: Nishant Kheterpal Date: Mon, 3 Dec 2018 17:08:47 -0800 Subject: [PATCH 25/25] localdocker --- docs/source/rllabec2.rst | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/docs/source/rllabec2.rst b/docs/source/rllabec2.rst index af617f1e2..cf1bd9318 100644 --- a/docs/source/rllabec2.rst +++ b/docs/source/rllabec2.rst @@ -43,10 +43,11 @@ you are using already-existing network files (from, say, OpenStreetMap), ensure they do not get deleted by ``make clean`` by storing such files elsewhere. -Inside the experiment, change the ``mode`` to ``ec2`` (other options are -``local`` and ``local_docker``). You should run the experiment in +Inside the experiment, change the ``mode`` to ``ec2``. Other mode options are +``local``, which uses your standard environment and ``local_docker``, which +uses a local Docker image to run the experiment. You should run the experiment in ``local_docker`` mode briefly before running the ``ec2`` version to -ensure there are no errors, particularly with Docker image compatability +ensure there are no errors, particularly with Docker image compatibility. After running ``python example.py`` once the ``mode`` of ``example.py`` is ``ec2``, you should see your experiment running on AWS.