Skip to content

Commit

Permalink
improved scenarios
Browse files Browse the repository at this point in the history
  • Loading branch information
joel-mb committed Dec 21, 2020
1 parent 4318627 commit 2b99edb
Show file tree
Hide file tree
Showing 9 changed files with 20 additions and 12 deletions.
2 changes: 1 addition & 1 deletion examples/carla/Carla_Challenge/carlaChallenge10.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,6 @@ ego = Car at ego_spawn_pt,
adversary = Car at adv_spawn_pt,
with behavior AdversaryBehavior(adv_trajectory)

require (distance to intersec) in Range(15, 20)
require (distance to intersec) in Range(20, 25)
require (distance from adversary to intersec) in Range(15, 20)
terminate when (distance to ego_spawn_pt) > 70
2 changes: 1 addition & 1 deletion examples/carla/Carla_Challenge/carlaChallenge4.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,6 @@ bicycle = Bicycle at spotBicycle offset by 3.5@0,
with behavior BicycleBehavior(BICYCLE_MIN_SPEED, THRESHOLD),
with regionContainedIn None

require (distance to intersec) in Range(10, 25)
require (distance to intersec) in Range(10, 15)
require (distance from bicycle to intersec) in Range(10, 15)
terminate when (distance to spot) > 50
10 changes: 5 additions & 5 deletions examples/carla/Carla_Challenge/carlaChallenge6.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@ traffic
"""

## SET MAP AND MODEL (i.e. definitions of all referenceable vehicle types, road library, etc)
param map = localPath('../../../tests/formats/opendrive/maps/CARLA/Town07.xodr') # or other CARLA map that definitely works
param carla_map = 'Town07'
param map = localPath('../../../tests/formats/opendrive/maps/CARLA/Town01.xodr') # or other CARLA map that definitely works
param carla_map = 'Town01'
model scenic.simulators.carla.model

## CONSTANTS
Expand All @@ -16,7 +16,7 @@ EGO_SPEED = 7
ONCOMING_CAR_SPEED = 10
BLOCKING_CAR_DIST = Range(15, 20)
BREAK_INTENSITY = 0.8
DIST_THRESHOLD = 13
DIST_THRESHOLD = 15

## DEFINING BEHAVIORS
behavior EgoBehavior():
Expand Down Expand Up @@ -69,6 +69,6 @@ blockingCar = Car following roadDirection for BLOCKING_CAR_DIST,

## EXPLICIT HARD CONSTRAINTS
require blockingCar can see oncomingCar
require (distance from blockingCar to oncomingCar) < 10
require (distance from blockingCar to intersection) > 10
require (distance from blockingCar to oncomingCar) in Range(5, 15)
require (distance from blockingCar to intersection) > 50
require (ego.laneSection.isForward != oncomingCar.laneSection.isForward)
2 changes: 1 addition & 1 deletion examples/carla/Carla_Challenge/carlaChallenge7.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -77,4 +77,4 @@ adversary = Car at adv_spawn_pt,

require (distance to intersec) in Range(15, 20)
require (distance from adversary to intersec) in Range(10, 15)
terminate when (distance to ego_spawn_pt) > 70
terminate when (distance to ego_spawn_pt) > 70
7 changes: 5 additions & 2 deletions examples/carla/manual_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@
ESC : quit
"""


from __future__ import print_function

# ==============================================================================
Expand Down Expand Up @@ -164,7 +165,7 @@ def restart(self):
print("Ego vehicle found")
self.player = vehicle
break

self.player_name = self.player.type_id

# Set up the sensors.
Expand All @@ -174,7 +175,9 @@ def restart(self):

def tick(self, clock):
if len(self.world.get_actors().filter(self.player_name)) < 1:
return False
self.player = None
self.destroy()
self.restart()

self.hud.tick(self, clock)
return True
Expand Down
1 change: 1 addition & 0 deletions examples/carla/manual_control/carlaChallenge1.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ its original lane.
## SET MAP AND MODEL (i.e. definitions of all referenceable vehicle types, road library, etc)
param map = localPath('../../../tests/formats/opendrive/maps/CARLA/Town01.xodr') # or other CARLA map that definitely works
param carla_map = 'Town01'
param render = '0'
model scenic.simulators.carla.model

## CONSTANTS
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ emergency brake or an avoidance maneuver.
# SET MAP AND MODEL (i.e. definitions of all referenceable vehicle types, road library, etc)
param map = localPath('../../../tests/formats/opendrive/maps/CARLA/Town05.xodr') # or other CARLA map that definitely works
param carla_map = 'Town05'
param render = '0'
model scenic.simulators.carla.model

# CONSTANTS
Expand Down
6 changes: 4 additions & 2 deletions examples/carla/manual_control/carlaChallenge4.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ emergency brake or an avoidance maneuver.
## SET MAP AND MODEL (i.e. definitions of all referenceable vehicle types, road library, etc)
param map = localPath('../../../tests/formats/opendrive/maps/CARLA/Town01.xodr') # or other CARLA map that definitely works
param carla_map = 'Town01'
param render = '0'
model scenic.simulators.carla.model

## CONSTANTS
Expand All @@ -26,7 +27,8 @@ startLane = Uniform(*intersec.incomingLanes)
maneuver = Uniform(*startLane.maneuvers)
ego_trajectory = [maneuver.startLane, maneuver.connectingLane, maneuver.endLane]

ego = Car in maneuver.startLane.centerline,
spot = OrientedPoint in maneuver.startLane.centerline
ego = Car at spot,
with blueprint EGO_MODEL,
with rolename 'hero'

Expand All @@ -39,4 +41,4 @@ bicycle = Bicycle at spotBicycle offset by 3.5@0,

require (distance to intersec) in Range(10,25)
require (distance from bicycle to intersec) in Range(5, 10)
terminate when (distance to spot) > 50
terminate when (distance to spot) > 50
1 change: 1 addition & 0 deletions examples/carla/manual_control/carlaChallenge7.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ forcing the ego-vehicle to avoid the collision.
## SET MAP AND MODEL (i.e. definitions of all referenceable vehicle types, road library, etc)
param map = localPath('../../../tests/formats/opendrive/maps/CARLA/Town05.xodr') # or other CARLA map that definitely works
param carla_map = 'Town05'
param render = '0'
model scenic.simulators.carla.model

## CONSTANTS
Expand Down

0 comments on commit 2b99edb

Please sign in to comment.