Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -120,3 +120,5 @@ venv.bak/
dmypy.json

*.cproject

examples/dynamic_rulebook/*/outputs/
3,808 changes: 3,808 additions & 0 deletions examples/dynamic_rulebook/maps/Town05.net.xml

Large diffs are not rendered by default.

47,273 changes: 47,273 additions & 0 deletions examples/dynamic_rulebook/maps/Town05.xodr

Large diffs are not rendered by default.

140 changes: 140 additions & 0 deletions examples/dynamic_rulebook/multi.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,140 @@
"""
Framework for experimentation of multi-objective and dynamic falsification.

Author: Kai-Chun Chang. Based on Kesav Viswanadha's code.
"""

import time
import os
import numpy as np
from dotmap import DotMap
import traceback
import argparse
import importlib

from verifai.samplers.scenic_sampler import ScenicSampler
from verifai.scenic_server import ScenicServer
from verifai.falsifier import generic_falsifier, generic_parallel_falsifier
from verifai.monitor import multi_objective_monitor, specification_monitor
from verifai.rulebook import rulebook

import networkx as nx
import pandas as pd

def announce(message):
lines = message.split('\n')
size = max([len(p) for p in lines]) + 4
def pad(line):
ret = '* ' + line
ret += ' ' * (size - len(ret) - 1) + '*'
return ret
lines = list(map(pad, lines))
m = '\n'.join(lines)
border = '*' * size
print(border)
print(m)
print(border)

"""
Runs all experiments in a directory.
"""
def run_experiments(path, rulebook=None, parallel=False, model=None,
sampler_type=None, headless=False, num_workers=5, output_dir='outputs',
experiment_name=None, max_time=None, n_iters=None, max_steps=300):
if not os.path.exists(output_dir):
os.mkdir(output_dir)
paths = []
if os.path.isdir(path):
for root, _, files in os.walk(path):
for name in files:
fname = os.path.join(root, name)
if os.path.splitext(fname)[1] == '.scenic':
paths.append(fname)
else:
paths = [path]
for p in paths:
falsifier = run_experiment(p, rulebook=rulebook,
parallel=parallel, model=model, sampler_type=sampler_type, headless=headless,
num_workers=num_workers, max_time=max_time, n_iters=n_iters, max_steps=max_steps)
df = pd.concat([falsifier.error_table.table, falsifier.safe_table.table])
if experiment_name is not None:
outfile = experiment_name
else:
root, _ = os.path.splitext(p)
outfile = root.split('/')[-1]
if parallel:
outfile += '_parallel'
if model:
outfile += f'_{model}'
if sampler_type:
outfile += f'_{sampler_type}'
outfile += '.csv'
outpath = os.path.join(output_dir, outfile)
print(f'(multi.py) Saving output to {outpath}')
df.to_csv(outpath)

"""
Runs a single falsification experiment.

Arguments:
path: Path to Scenic script to be run.
parallel: Whether or not to enable parallelism.
model: Which simulator model to use (e.g. scenic.simulators.newtonian.driving_model)
sampler_type: Which VerifAI sampelr to use (e.g. halton, scenic, ce, mab, etc.)
headless: Whether or not to display each simulation.
num_workers: Number of parallel workers. Only used if parallel is true.
"""
def run_experiment(scenic_path, rulebook=None, parallel=False, model=None,
sampler_type=None, headless=False, num_workers=5, max_time=None,
n_iters=5, max_steps=300):
# Construct rulebook
rb = rulebook

# Construct sampler (scenic_sampler.py)
print(f'(multi.py) Running Scenic script {scenic_path}')
params = {'verifaiSamplerType': sampler_type} if sampler_type else {}
params['render'] = not headless
params['seed'] = 0
params['use2DMap'] = True
sampler = ScenicSampler.fromScenario(scenic_path, maxIterations=40000, params=params, model=model)
num_objectives = sampler.scenario.params.get('N', 1)
s_type = sampler.scenario.params.get('verifaiSamplerType', None)
print(f'(multi.py) num_objectives: {num_objectives}')

# Construct falsifier (falsifier.py)
multi = num_objectives > 1
falsifier_params = DotMap(
n_iters=n_iters,
save_error_table=True,
save_safe_table=True,
max_time=max_time,
verbosity=1,
)
server_options = DotMap(maxSteps=max_steps, verbosity=1,
scenic_path=scenic_path, scenario_params=params, scenario_model=model,
num_workers=num_workers)
falsifier_class = generic_parallel_falsifier if parallel else generic_falsifier
falsifier = falsifier_class(monitor=rb, ## modified
sampler_type=s_type,
sampler=sampler,
falsifier_params=falsifier_params,
server_options=server_options,
server_class=ScenicServer)
print(f'(multi.py) sampler_type: {falsifier.sampler_type}')

# Run falsification
t0 = time.time()
print('(multi.py) Running falsifier')
falsifier.run_falsifier()
t = time.time() - t0
print()
print(f'(multi.py) Generated {len(falsifier.samples)} samples in {t} seconds with {falsifier.num_workers} workers')
print(f'(multi.py) Number of counterexamples: {len(falsifier.error_table.table)}')
if not parallel:
print(f'(multi.py) Sampling time: {falsifier.total_sample_time}')
print(f'(multi.py) Simulation time: {falsifier.total_simulate_time}')
print(f'(multi.py) Confidence interval: {falsifier.get_confidence_interval()}')
return falsifier

if __name__ == '__main__':
pass
50 changes: 50 additions & 0 deletions examples/dynamic_rulebook/multi_01/multi_01.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
import sys
import os
sys.path.append(os.path.abspath("."))
import random
import numpy as np

from multi import *
from multi_01_rulebook import rulebook_multi01

if __name__ == '__main__':
parser = argparse.ArgumentParser()
parser.add_argument('--scenic-path', '-sp', type=str, default='uberCrashNewton.scenic',
help='Path to Scenic script')
parser.add_argument('--graph-path', '-gp', type=str, default=None,
help='Path to graph file')
parser.add_argument('--rule-path', '-rp', type=str, default=None,
help='Path to rule file')
parser.add_argument('--output-dir', '-o', type=str, default=None,
help='Directory to save output trajectories')
parser.add_argument('--output-csv-dir', '-co', type=str, default=None,
help='Directory to save output error tables (csv files)')
parser.add_argument('--parallel', action='store_true')
parser.add_argument('--num-workers', type=int, default=5, help='Number of parallel workers')
parser.add_argument('--sampler-type', '-s', type=str, default=None,
help='verifaiSamplerType to use')
parser.add_argument('--experiment-name', '-e', type=str, default=None,
help='verifaiSamplerType to use')
parser.add_argument('--model', '-m', type=str, default='scenic.simulators.newtonian.driving_model')
parser.add_argument('--headless', action='store_true')
parser.add_argument('--n-iters', '-n', type=int, default=None, help='Number of simulations to run')
parser.add_argument('--max-time', type=int, default=None, help='Maximum amount of time to run simulations')
parser.add_argument('--single-graph', action='store_true', help='Only a unified priority graph')
parser.add_argument('--seed', type=int, default=0, help='Random seed')
parser.add_argument('--using-sampler', type=int, default=-1, help='Assigning sampler to use')
parser.add_argument('--exploration-ratio', type=float, default=2.0, help='Exploration ratio')
args = parser.parse_args()
if args.n_iters is None and args.max_time is None:
raise ValueError('At least one of --n-iters or --max-time must be set')

random.seed(args.seed)
np.random.seed(args.seed)

print('output_dir =', args.output_dir)
rb = rulebook_multi01(args.graph_path, args.rule_path, save_path=args.output_dir, single_graph=args.single_graph, using_sampler=args.using_sampler, exploration_ratio=args.exploration_ratio)
run_experiments(args.scenic_path, rulebook=rb,
parallel=args.parallel, model=args.model,
sampler_type=args.sampler_type, headless=args.headless,
num_workers=args.num_workers, output_dir=args.output_csv_dir, experiment_name=args.experiment_name,
max_time=args.max_time, n_iters=args.n_iters)

93 changes: 93 additions & 0 deletions examples/dynamic_rulebook/multi_01/multi_01.scenic
Original file line number Diff line number Diff line change
@@ -0,0 +1,93 @@
"""
TITLE: Multi 01
AUTHOR: Kai-Chun Chang, [email protected]
DESCRIPTION: The ego vehicle is driving along its lane when it encounters a blocking car ahead. The ego attempts to change to the opposite lane to bypass the blocking car before returning to its original lane.
"""

#################################
# MAP AND MODEL #
#################################

param map = localPath('../maps/Town05.xodr')
param carla_map = 'Town05'
param N = 2
model scenic.domains.driving.model

#################################
# CONSTANTS #
#################################

MODEL = 'vehicle.lincoln.mkz_2017'

param EGO_SPEED = VerifaiRange(6, 9) #7
param DIST_THRESHOLD = VerifaiRange(12, 14) #13
param BLOCKING_CAR_DIST = VerifaiRange(15, 20)
param BYPASS_DIST = VerifaiRange(4, 6) #5

DIST_TO_INTERSECTION = 15
TERM_DIST = 40

#################################
# AGENT BEHAVIORS #
#################################

behavior EgoBehavior(path):
current_lane = network.laneAt(self)
laneChangeCompleted = False
bypassed = False
try:
do FollowLaneBehavior(globalParameters.EGO_SPEED, laneToFollow=current_lane)
interrupt when (distance to blockingCar) < globalParameters.DIST_THRESHOLD and not laneChangeCompleted:
do LaneChangeBehavior(path, is_oppositeTraffic=True, target_speed=globalParameters.EGO_SPEED)
do FollowLaneBehavior(globalParameters.EGO_SPEED, is_oppositeTraffic=True) until (distance to blockingCar) > globalParameters.BYPASS_DIST
laneChangeCompleted = True
interrupt when (blockingCar can see ego) and (distance to blockingCar) > globalParameters.BYPASS_DIST and not bypassed:
current_laneSection = network.laneSectionAt(self)
rightLaneSec = current_laneSection._laneToLeft
do LaneChangeBehavior(rightLaneSec, is_oppositeTraffic=False, target_speed=globalParameters.EGO_SPEED)
bypassed = True

#################################
# SPATIAL RELATIONS #
#################################

#Find lanes that have a lane to their left in the opposite direction
laneSecsWithLeftLane = []
for lane in network.lanes:
for laneSec in lane.sections:
if laneSec._laneToLeft is not None:
if laneSec._laneToLeft.isForward is not laneSec.isForward:
laneSecsWithLeftLane.append(laneSec)

assert len(laneSecsWithLeftLane) > 0, \
'No lane sections with adjacent left lane with opposing \
traffic direction in network.'

initLaneSec = Uniform(*laneSecsWithLeftLane)
leftLaneSec = initLaneSec._laneToLeft

spawnPt = new OrientedPoint on initLaneSec.centerline

#################################
# SCENARIO SPECIFICATION #
#################################

ego = new Car at spawnPt,
with blueprint MODEL,
with behavior EgoBehavior(leftLaneSec)

blockingCar = new Car following roadDirection from ego for globalParameters.BLOCKING_CAR_DIST,
with blueprint MODEL,
with viewAngle 90 deg

require (distance from blockingCar to intersection) > DIST_TO_INTERSECTION
terminate when (distance to spawnPt) > TERM_DIST

#################################
# RECORDING #
#################################

record initial (initLaneSec.polygon.exterior.coords) as initLaneCoords
record initial (leftLaneSec.polygon.exterior.coords) as leftLaneCoords
record (ego.lane is initLaneSec.lane) as egoIsInInitLane
record (ego.lane is leftLaneSec.lane) as egoIsInLeftLane
5 changes: 5 additions & 0 deletions examples/dynamic_rulebook/multi_01/multi_01.sgraph
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
# ID 0
# Node list
0 on rule0 monitor
1 on rule1 monitor
# Edge list
6 changes: 6 additions & 0 deletions examples/dynamic_rulebook/multi_01/multi_01_00.graph
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
# ID 0
# Node list
0 on rule0 monitor
1 on rule1 monitor
# Edge list
1 0
6 changes: 6 additions & 0 deletions examples/dynamic_rulebook/multi_01/multi_01_01.graph
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
# ID 1
# Node list
0 on rule0 monitor
1 on rule1 monitor
# Edge list
0 1
5 changes: 5 additions & 0 deletions examples/dynamic_rulebook/multi_01/multi_01_02.graph
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
# ID 2
# Node list
0 off rule0 monitor
1 on rule1 monitor
# Edge list
53 changes: 53 additions & 0 deletions examples/dynamic_rulebook/multi_01/multi_01_rulebook.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
import numpy as np

from verifai.rulebook import rulebook

class rulebook_multi01(rulebook):
iteration = 0

def __init__(self, graph_path, rule_file, save_path=None, single_graph=False, using_sampler=-1, exploration_ratio=2.0):
rulebook.using_sampler = using_sampler
rulebook.exploration_ratio = exploration_ratio
super().__init__(graph_path, rule_file, single_graph=single_graph)
self.save_path = save_path

def evaluate(self, traj):
# Extract trajectory information
positions = np.array(traj.result.trajectory)
init_lane_coords = np.array(traj.result.records["initLaneCoords"])
left_lane_coords = np.array(traj.result.records["leftLaneCoords"])
ego_is_in_init_lane = np.array(traj.result.records["egoIsInInitLane"])
ego_is_in_left_lane = np.array(traj.result.records["egoIsInLeftLane"])

# Find switching points
switch_idx_1 = len(traj.result.trajectory)
switch_idx_2 = len(traj.result.trajectory)
distances_to_obs = positions[:, 0, :] - positions[:, 1, :]
distances_to_obs = np.linalg.norm(distances_to_obs, axis=1)
for i in range(len(distances_to_obs)):
if distances_to_obs[i] < 8.5 and switch_idx_1 == len(traj.result.trajectory):
switch_idx_1 = i
continue
if distances_to_obs[i] > 10 and switch_idx_1 < len(traj.result.trajectory) and switch_idx_2 == len(traj.result.trajectory):
switch_idx_2 = i
break
assert switch_idx_1 < len(traj.result.trajectory), "Switching point 1 cannot be found"

# Evaluation
indices_0 = np.arange(0, switch_idx_1)
indices_1 = np.arange(switch_idx_1, switch_idx_2)
indices_2 = np.arange(switch_idx_2, len(traj.result.trajectory))
if self.single_graph:
rho0 = self.evaluate_segment(traj, 0, indices_0)
rho1 = self.evaluate_segment(traj, 0, indices_1)
rho2 = self.evaluate_segment(traj, 0, indices_2)
print('Actual rho:')
print(rho0[0], rho0[1])
print(rho1[0], rho1[1])
print(rho2[0], rho2[1])
rho = self.evaluate_segment(traj, 0, np.arange(0, len(traj.result.trajectory)))
return np.array([rho])
rho0 = self.evaluate_segment(traj, 0, indices_0)
rho1 = self.evaluate_segment(traj, 1, indices_1)
rho2 = self.evaluate_segment(traj, 2, indices_2)
return np.array([rho0, rho1, rho2])
19 changes: 19 additions & 0 deletions examples/dynamic_rulebook/multi_01/multi_01_spec.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
import numpy as np

def rule0(simulation, indices): # safe distance to obstacle
if indices.size == 0:
return 1
positions = np.array(simulation.result.trajectory)
distances_to_adv1 = positions[indices, [0], :] - positions[indices, [1], :]
distances_to_adv1 = np.linalg.norm(distances_to_adv1, axis=1)
rho = np.min(distances_to_adv1, axis=0) - 3
return rho

def rule1(simulation, indices): # ego is in the left lane
if indices.size == 0:
return 1
ego_is_in_left_lane = np.array(simulation.result.records["egoIsInLeftLane"], dtype=bool)
for i in indices:
if ego_is_in_left_lane[i][1]:
return -1
return 1
Loading