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
11 changes: 10 additions & 1 deletion .github/workflows/run-simulators.yml
Original file line number Diff line number Diff line change
Expand Up @@ -144,10 +144,19 @@ jobs:
ssh -o StrictHostKeyChecking=no -o ServerAliveInterval=60 -o ServerAliveCountMax=3 -i private_key ${USER_NAME}@${HOSTNAME} '
cd /home/ubuntu/actions/Scenic &&
source venv/bin/activate &&
carla_versions=($(find /software -maxdepth 1 -type d -name 'carla*')) &&
# run carla0.9.15 first
carla_versions=($(find /software -maxdepth 1 -type d -name 'carla*' | sort -V)) &&
for version in "${carla_versions[@]}"; do
echo "============================= CARLA $version ============================="
export CARLA_ROOT="$version"

# install local wheel for carla0.10.0
if [[ "$version" == "/software/carla0.10.0" ]]; then
WHL=$(ls "$version"/PythonAPI/carla/dist/carla-0.10.0-cp310-cp310-linux_x86_64.whl)
echo "Installing local wheel: $WHL"
python3 -m pip install --force-reinstall "$WHL"
fi

pytest tests/simulators/carla
done
'
Expand Down
17,962 changes: 17,962 additions & 0 deletions assets/maps/CARLA/Town10HD_Opt.xodr

Large diffs are not rendered by default.

22 changes: 19 additions & 3 deletions docs/simulators.rst
Original file line number Diff line number Diff line change
Expand Up @@ -57,14 +57,23 @@ Our interface to the `CARLA <https://carla.org/>`_ simulator enables using Sceni
The interface supports dynamic scenarios written using the CARLA world model (:obj:`scenic.simulators.carla.model`) as well as scenarios using the cross-platform :ref:`driving_domain`.
To use the interface, please follow these instructions:

1. Install the latest version of CARLA (we've tested versions 0.9.9 through 0.9.14) from the `CARLA Release Page <https://github.com/carla-simulator/carla/releases>`_.
Note that CARLA currently only supports Linux and Windows.
1. Install the latest version of CARLA (we've tested versions 0.9.9 through 0.10.0) from the `CARLA Release Page <https://github.com/carla-simulator/carla/releases>`_.
Note that CARLA currently only supports Linux and Windows. If you plan to use **0.10.0**, double-check its higher system requirements in the `CARLA UE5 quick-start guide <https://carla-ue5.readthedocs.io/en/latest/start_quickstart/>`_.
2. Install Scenic in your Python virtual environment as instructed in :ref:`quickstart`.
3. Within the same virtual environment, install CARLA's Python API.
How to do this depends on the CARLA version and whether you built it from source:

.. tabs::

.. tab:: 0.10.0

If you're using **CARLA 0.10.0** (not yet on PyPI), install the client wheel that ships with the simulator:

.. code-block:: text

cd CARLA_ROOT/PythonAPI/dist/
python3 -m pip install carla-*.*.*-cp3*-linux_x86_64.whl

.. tab:: 0.9.12+

Run the following command, replacing ``X.Y.Z`` with the version of CARLA you installed:
Expand Down Expand Up @@ -99,9 +108,16 @@ To use the interface, please follow these instructions:
You can check that the ``carla`` package was correctly installed by running :command:`python -c 'import carla'`: if it prints ``No module named 'carla'``, the installation didn't work.
We suggest upgrading to a newer version of CARLA so that you can use :command:`pip` to install the Python API.

To start CARLA, run the command :command:`./CarlaUE4.sh` in your CARLA folder.
To start CARLA, run the command :command:`./CarlaUE4.sh` in your CARLA folder (for **CARLA 0.10.0**, use :command:`./CarlaUnreal.sh` instead).
Once CARLA is running, you can run dynamic Scenic scenarios following the instructions in :ref:`the dynamics tutorial <dynamics_running_examples>`.

.. note:: CARLA 0.10.0 compatibility

- All ``examples/carla`` scenarios now support both CARLA 0.9.x and 0.10.0.
- Only the **Town10HD_Opt** map is available in 0.10.0.
- The 0.10.0 blueprint library is different (for example, bicycle blueprints are currently unavailable).
- There are some differences in physics in 0.10.0 (for example, pedestrians movement is slower).


Grand Theft Auto V
------------------
Expand Down
6 changes: 3 additions & 3 deletions examples/carla/Carla_Challenge/carlaChallenge1.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,12 @@ To run this file using the Carla simulator:
"""

## SET MAP AND MODEL (i.e. definitions of all referenceable vehicle types, road library, etc)
param map = localPath('../../../assets/maps/CARLA/Town01.xodr')
param carla_map = 'Town01'
param map = localPath('../../../assets/maps/CARLA/Town10HD_Opt.xodr')
param carla_map = 'Town10HD_Opt'
model scenic.simulators.carla.model

## CONSTANTS
EGO_MODEL = "vehicle.lincoln.mkz_2017"
EGO_MODEL = "vehicle.nissan.patrol"
EGO_SPEED = 10

## DEFINING BEHAVIORS
Expand Down
9 changes: 6 additions & 3 deletions examples/carla/Carla_Challenge/carlaChallenge10.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,12 @@ To run this file using the Carla simulator:
"""

## SET MAP AND MODEL (i.e. definitions of all referenceable vehicle types, road library, etc)
param map = localPath('../../../assets/maps/CARLA/Town05.xodr')
param carla_map = 'Town05'
param map = localPath('../../../assets/maps/CARLA/Town10HD_Opt.xodr')
param carla_map = 'Town10HD_Opt'
model scenic.simulators.carla.model

## CONSTANTS
EGO_MODEL = "vehicle.lincoln.mkz_2017"
EGO_MODEL = "vehicle.nissan.patrol"
EGO_SPEED = 10
SAFETY_DISTANCE = 20
BRAKE_INTENSITY = 1.0
Expand All @@ -36,6 +36,9 @@ behavior EgoBehavior(speed, trajectory):

fourWayIntersection = filter(lambda i: i.is4Way and not i.isSignalized, network.intersections)

if not fourWayIntersection:
raise RuntimeError("This map doesn't have any four-way unsignalized intersections.")

# make sure to put '*' to uniformly randomly select from all elements of the list
intersec = Uniform(*fourWayIntersection)
ego_start_lane = Uniform(*intersec.incomingLanes)
Expand Down
10 changes: 5 additions & 5 deletions examples/carla/Carla_Challenge/carlaChallenge2.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,12 @@ To run this file using the Carla simulator:
"""

## SET MAP AND MODEL (i.e. definitions of all referenceable vehicle types, road library, etc)
param map = localPath('../../../assets/maps/CARLA/Town01.xodr')
param carla_map = 'Town01'
param map = localPath('../../../assets/maps/CARLA/Town10HD_Opt.xodr')
param carla_map = 'Town10HD_Opt'
model scenic.simulators.carla.model

## CONSTANTS
EGO_MODEL = "vehicle.lincoln.mkz_2017"
EGO_MODEL = "vehicle.nissan.patrol"
EGO_SPEED = 10
EGO_BRAKING_THRESHOLD = 12

Expand All @@ -34,7 +34,7 @@ behavior EgoBehavior(speed=10):

# LEAD CAR BEHAVIOR: Follow lane, and brake after passing a threshold distance to obstacle
behavior LeadingCarBehavior(speed=10):
try:
try:
do FollowLaneBehavior(speed)

interrupt when withinDistanceToAnyObjs(self, LEADCAR_BRAKING_THRESHOLD):
Expand All @@ -56,5 +56,5 @@ ego = new Car following roadDirection from leadCar for Range(-15, -10),
with blueprint EGO_MODEL,
with behavior EgoBehavior(EGO_SPEED)

require (distance to intersection) > 80
require (distance to intersection) > 50
terminate when ego.speed < 0.1 and (distance to obstacle) < 30
21 changes: 14 additions & 7 deletions examples/carla/Carla_Challenge/carlaChallenge3_dynamic.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,12 @@ To run this file using the Carla simulator:
"""

# SET MAP AND MODEL (i.e. definitions of all referenceable vehicle types, road library, etc)
param map = localPath('../../../assets/maps/CARLA/Town05.xodr')
param carla_map = 'Town05'
param map = localPath('../../../assets/maps/CARLA/Town10HD_Opt.xodr')
param carla_map = 'Town10HD_Opt'
model scenic.simulators.carla.model

# CONSTANTS
EGO_MODEL = "vehicle.lincoln.mkz_2017"
EGO_MODEL = "vehicle.nissan.patrol"
EGO_SPEED = 10
SAFETY_DISTANCE = 10
BRAKE_INTENSITY = 1.0
Expand All @@ -36,8 +36,15 @@ behavior PedestrianBehavior(min_speed=1, threshold=10):
# Please refer to scenic/domains/driving/roads.py how to access detailed road infrastructure
# 'network' is the 'class Network' object in roads.py

# make sure to put '*' to uniformly randomly select from all elements of the list, 'network.lanes'
lane = Uniform(*network.lanes)
# collect all the curb-side lanes
curbLanes = [
lg.lanes[0]
for lg in network.laneGroups
if lg is lg.road.forwardLanes
]

# make sure to put '*' to uniformly randomly select from all elements of the list
lane = Uniform(*curbLanes)

spot = new OrientedPoint on lane.centerline
vending_spot = new OrientedPoint following roadDirection from spot for -3
Expand All @@ -55,6 +62,6 @@ ego = new Car following roadDirection from spot for Range(-30, -20),
with blueprint EGO_MODEL,
with behavior EgoBehavior(EGO_SPEED)

require (distance to intersection) > 75
require (distance to intersection) > 40
require (ego.laneSection._slowerLane is None)
terminate when (distance to spot) > 50
terminate when (distance to spot) > 50
6 changes: 3 additions & 3 deletions examples/carla/Carla_Challenge/carlaChallenge3_static.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,12 @@ To run this file using the Carla simulator:
"""

## SET MAP AND MODEL (i.e. definitions of all referenceable vehicle types, road library, etc)
param map = localPath('../../../assets/maps/CARLA/Town01.xodr')
param carla_map = 'Town01'
param map = localPath('../../../assets/maps/CARLA/Town10HD_Opt.xodr')
param carla_map = 'Town10HD_Opt'
model scenic.simulators.carla.model

## CONSTANTS
EGO_MODEL = "vehicle.lincoln.mkz_2017"
EGO_MODEL = "vehicle.nissan.patrol"
EGO_SPEED = 10
EGO_BRAKING_THRESHOLD = 12

Expand Down
6 changes: 3 additions & 3 deletions examples/carla/Carla_Challenge/carlaChallenge4.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,12 @@ To run this file using the Carla simulator:
"""

## SET MAP AND MODEL (i.e. definitions of all referenceable vehicle types, road library, etc)
param map = localPath('../../../assets/maps/CARLA/Town01.xodr')
param carla_map = 'Town01'
param map = localPath('../../../assets/maps/CARLA/Town10HD_Opt.xodr')
param carla_map = 'Town10HD_Opt'
model scenic.simulators.carla.model

## CONSTANTS
EGO_MODEL = "vehicle.lincoln.mkz_2017"
EGO_MODEL = "vehicle.nissan.patrol"
BICYCLE_MIN_SPEED = 1.5
THRESHOLD = 18
BRAKE_ACTION = 1.0
Expand Down
8 changes: 4 additions & 4 deletions examples/carla/Carla_Challenge/carlaChallenge5.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@ Ego-vehicle performs a lane changing to evade a leading vehicle, which is moving
To run this file using the Carla simulator:
scenic examples/carla/Carla_Challenge/carlaChallenge5.scenic --2d --model scenic.simulators.carla.model --simulate
"""
param map = localPath('../../../assets/maps/CARLA/Town05.xodr')
param carla_map = 'Town05'
param map = localPath('../../../assets/maps/CARLA/Town10HD_Opt.xodr')
param carla_map = 'Town10HD_Opt'
model scenic.simulators.carla.model

#CONSTANTS
Expand All @@ -19,7 +19,7 @@ DIST_THRESHOLD = 15
behavior EgoBehavior(leftpath, origpath=[]):
laneChangeCompleted = False

try:
try:
do FollowLaneBehavior(EGO_SPEED)

interrupt when withinDistanceToAnyObjs(self, DIST_THRESHOLD) and not laneChangeCompleted:
Expand Down Expand Up @@ -53,4 +53,4 @@ cyclist = new Car following roadDirection from ego for EGO_TO_BICYCLE,
with behavior SlowCarBehavior()

require (distance from ego to intersection) > 10
require (distance from cyclist to intersection) > 10
require (distance from cyclist to intersection) > 10
8 changes: 4 additions & 4 deletions examples/carla/Carla_Challenge/carlaChallenge6.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,8 @@ To run this file using the Carla simulator:

# N.B. Town07 is not included with CARLA by default; see installation instructions at
# https://carla.readthedocs.io/en/latest/start_quickstart/#import-additional-assets
param map = localPath('../../../assets/maps/CARLA/Town07.xodr')
param carla_map = 'Town07'
param map = localPath('../../../assets/maps/CARLA/Town10HD_Opt.xodr')
param carla_map = 'Town10HD_Opt'
model scenic.simulators.carla.model


Expand Down Expand Up @@ -81,11 +81,11 @@ oncomingCar = new Car on leftLaneSec.centerline,

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

blockingCar = new Car following roadDirection from ego for BLOCKING_CAR_DIST,
with viewAngle 90 deg

#Make sure the oncoming Car is at a visible section of the lane
require blockingCar can see oncomingCar
require (distance from blockingCar to oncomingCar) < DIST_BTW_BLOCKING_ONCOMING_CARS
require (distance from blockingCar to intersection) > DIST_TO_INTERSECTION
require (distance from blockingCar to intersection) > DIST_TO_INTERSECTION
12 changes: 6 additions & 6 deletions examples/carla/Carla_Challenge/carlaChallenge7.scenic
Original file line number Diff line number Diff line change
@@ -1,14 +1,14 @@
""" Scenario Description
Based on 2019 Carla Challenge Traffic Scenario 07.
Ego-vehicle is going straight at an intersection but a crossing vehicle
Ego-vehicle is going straight at an intersection but a crossing vehicle
runs a red light, forcing the ego-vehicle to perform a collision avoidance maneuver.
Note: The traffic light control is not implemented yet, but it will soon be.
Note: The traffic light control is not implemented yet, but it will soon be.

To run this file using the Carla simulator:
scenic examples/carla/Carla_Challenge/carlaChallenge7.scenic --2d --model scenic.simulators.carla.model --simulate
"""
param map = localPath('../../../assets/maps/CARLA/Town05.xodr')
param carla_map = 'Town05'
param map = localPath('../../../assets/maps/CARLA/Town10HD_Opt.xodr')
param carla_map = 'Town10HD_Opt'
model scenic.simulators.carla.model

DELAY_TIME_1 = 1 # the delay time for ego
Expand All @@ -26,7 +26,7 @@ behavior CrossingCarBehavior(trajectory):
do FollowTrajectoryBehavior(trajectory = trajectory)

behavior EgoBehavior(trajectory):

try:
do FollowTrajectoryBehavior(trajectory=trajectory)
interrupt when withinDistanceToAnyObjs(self, SAFETY_DISTANCE):
Expand Down Expand Up @@ -57,4 +57,4 @@ crossing_car = new Car following roadDirection from csm_spwPt for DISTANCE_TO_IN
with behavior CrossingCarBehavior(crossing_car_trajectory)


"""Note: Traffic light is currently not controlled but this functionality will be added very soon """
"""Note: Traffic light is currently not controlled but this functionality will be added very soon """
9 changes: 4 additions & 5 deletions examples/carla/Carla_Challenge/carlaChallenge8.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,12 @@ To run this file using the Carla simulator:
"""

## SET MAP AND MODEL (i.e. definitions of all referenceable vehicle types, road library, etc)
param map = localPath('../../../assets/maps/CARLA/Town05.xodr')
param carla_map = 'Town05'
param map = localPath('../../../assets/maps/CARLA/Town10HD_Opt.xodr')
param carla_map = 'Town10HD_Opt'
model scenic.simulators.carla.model

## CONSTANTS
EGO_MODEL = "vehicle.lincoln.mkz_2017"
EGO_MODEL = "vehicle.nissan.patrol"
EGO_SPEED = 10
SAFETY_DISTANCE = 20
BRAKE_INTENSITY = 1.0
Expand Down Expand Up @@ -78,7 +78,6 @@ ego = new Car at ego_spawn_pt,
adversary = new Car at adv_spawn_pt,
with behavior AdversaryBehavior(adv_trajectory)

require (ego_start_section.laneToLeft == adv_end_section) # make sure the ego and adversary are spawned in opposite lanes
require 25 <= (distance to intersec) <= 30
require 10 <= (distance to intersec) <= 30
require 15 <= (distance from adversary to intersec) <= 20
terminate when (distance to ego_spawn_pt) > 70
4 changes: 2 additions & 2 deletions examples/carla/Carla_Challenge/carlaChallenge9.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@ Ego-vehicle is performing a right turn at an intersection, yielding to crossing
To run this file using the Carla simulator:
scenic examples/carla/Carla_Challenge/carlaChallenge9.scenic --2d --model scenic.simulators.carla.model --simulate
"""
param map = localPath('../../../assets/maps/CARLA/Town05.xodr')
param carla_map = 'Town05'
param map = localPath('../../../assets/maps/CARLA/Town10HD_Opt.xodr')
param carla_map = 'Town10HD_Opt'
model scenic.simulators.carla.model

DELAY_TIME_1 = 1 # the delay time for ego
Expand Down
12 changes: 6 additions & 6 deletions examples/carla/NHTSA_Scenarios/bypassing/bypassing_01.scenic
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
"""
TITLE: Bypassing 01
AUTHOR: Francis Indaheng, findaheng@berkeley.edu
DESCRIPTION: Ego vehicle performs a lane change to bypass a slow
DESCRIPTION: Ego vehicle performs a lane change to bypass a slow
adversary vehicle before returning to its original lane.
SOURCE: NHSTA, #16

Expand All @@ -13,22 +13,22 @@ To run this file using the Carla simulator:
# MAP AND MODEL #
#################################

param map = localPath('../../../../assets/maps/CARLA/Town03.xodr')
param carla_map = 'Town03'
param map = localPath('../../../../assets/maps/CARLA/Town10HD_Opt.xodr')
param carla_map = 'Town10HD_Opt'
model scenic.simulators.carla.model

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

MODEL = 'vehicle.lincoln.mkz_2017'
MODEL = 'vehicle.nissan.patrol'

param EGO_SPEED = VerifaiRange(7, 10)

param ADV_DIST = VerifaiRange(10, 25)
param ADV_SPEED = VerifaiRange(2, 4)

BYPASS_DIST = [15, 10]
BYPASS_DIST = [20, 15]
INIT_DIST = 50
TERM_TIME = 5

Expand All @@ -53,7 +53,7 @@ behavior EgoBehavior():
laneSectionToSwitch=slowerLaneSec,
target_speed=globalParameters.EGO_SPEED)
do FollowLaneBehavior(target_speed=globalParameters.EGO_SPEED) for TERM_TIME seconds
terminate
terminate

#################################
# SPATIAL RELATIONS #
Expand Down
Loading
Loading