Skip to content

Commit

Permalink
CARLA 0.10 support
Browse files Browse the repository at this point in the history
  • Loading branch information
glopezdiest committed Dec 9, 2024
1 parent fe28e13 commit 310226e
Show file tree
Hide file tree
Showing 15 changed files with 69 additions and 87 deletions.
File renamed without changes.
6 changes: 3 additions & 3 deletions examples/carla/Carla_Challenge/carlaChallenge1.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,12 @@ its original lane.
"""

## 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.lincoln.mkz"
EGO_SPEED = 10

## DEFINING BEHAVIORS
Expand Down
6 changes: 3 additions & 3 deletions examples/carla/Carla_Challenge/carlaChallenge10.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,12 @@ this situation it is assumed that the first to enter the intersection has priori
"""

## 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.lincoln.mkz"
EGO_SPEED = 10
SAFETY_DISTANCE = 20
BRAKE_INTENSITY = 1.0
Expand Down
8 changes: 4 additions & 4 deletions examples/carla/Carla_Challenge/carlaChallenge2.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,12 @@ emergency brake or an avoidance maneuver.
"""

## 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.lincoln.mkz"
EGO_SPEED = 10
EGO_BRAKING_THRESHOLD = 12

Expand Down Expand Up @@ -53,5 +53,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
20 changes: 10 additions & 10 deletions examples/carla/Carla_Challenge/carlaChallenge3_dynamic.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -6,18 +6,18 @@ emergency brake or an avoidance maneuver.
"""

# 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_SPEED = 10
## CONSTANTS
EGO_MODEL = "vehicle.lincoln.mkz"
EGO_SPEED = 6
SAFETY_DISTANCE = 10
BRAKE_INTENSITY = 1.0

PEDESTRIAN_MIN_SPEED = 1.0
THRESHOLD = 20
PEDESTRIAN_MIN_SPEED = 2.0
THRESHOLD = 30

# EGO BEHAVIOR: Follow lane and brake when reaches threshold distance to obstacle
behavior EgoBehavior(speed=10):
Expand Down Expand Up @@ -48,10 +48,10 @@ vending_machine = new VendingMachine right of vending_spot by 3,
with heading -90 deg relative to vending_spot.heading,
with regionContainedIn None

ego = new Car following roadDirection from spot for Range(-30, -20),
ego = new Car following roadDirection from spot for Range(-50, -40),
with blueprint EGO_MODEL,
with behavior EgoBehavior(EGO_SPEED)

require (distance to intersection) > 75
require (distance to intersection) > 50
require (ego.laneSection._slowerLane is None)
terminate when (distance to spot) > 50
terminate when (distance to spot) > 30
8 changes: 4 additions & 4 deletions examples/carla/Carla_Challenge/carlaChallenge3_static.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,12 @@ emergency brake or an avoidance maneuver.
"""

## 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.lincoln.mkz"
EGO_SPEED = 10
EGO_BRAKING_THRESHOLD = 12

Expand Down Expand Up @@ -41,5 +41,5 @@ ego = new Car following roadDirection from spawnPt for Range(-50, -30),
with blueprint EGO_MODEL,
with behavior EgoBehavior(EGO_SPEED)

require (distance to intersection) > 75
require (distance to intersection) > 60
terminate when ego.speed < 0.1 and (distance to obstacle) < 15
8 changes: 4 additions & 4 deletions examples/carla/Carla_Challenge/carlaChallenge4.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -6,16 +6,16 @@ emergency brake or an avoidance maneuver.
"""

## 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.lincoln.mkz"
BICYCLE_MIN_SPEED = 1.5
THRESHOLD = 18
BRAKE_ACTION = 1.0
SAFETY_DISTANCE = 10
SAFETY_DISTANCE = 17

## DEFINING BEHAVIORS
behavior EgoBehavior(trajectory):
Expand Down
4 changes: 2 additions & 2 deletions examples/carla/Carla_Challenge/carlaChallenge5.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@
Based on 2019 Carla Challenge Traffic Scenario 05.
Ego-vehicle performs a lane changing to evade a leading vehicle, which is moving too slowly.
"""
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 Down
9 changes: 3 additions & 6 deletions examples/carla/Carla_Challenge/carlaChallenge6.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -4,13 +4,10 @@ Ego-vehicle must go around a blocking object
using the opposite lane, yielding to oncoming traffic.
"""

# 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


#CONSTANTS
ONCOMING_THROTTLE = 0.6
EGO_SPEED = 7
Expand Down Expand Up @@ -78,7 +75,7 @@ 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

Expand Down
7 changes: 2 additions & 5 deletions examples/carla/Carla_Challenge/carlaChallenge7.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@ 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.
"""
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 Expand Up @@ -52,6 +52,3 @@ ego = new Car following roadDirection from ego_spwPt for DISTANCE_TO_INTERSECTIO

crossing_car = new Car following roadDirection from csm_spwPt for DISTANCE_TO_INTERSECTION2,
with behavior CrossingCarBehavior(crossing_car_trajectory)


"""Note: Traffic light is currently not controlled but this functionality will be added very soon """
6 changes: 3 additions & 3 deletions examples/carla/Carla_Challenge/carlaChallenge8.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,12 @@ traffic.
"""

## 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.lincoln.mkz"
EGO_SPEED = 10
SAFETY_DISTANCE = 20
BRAKE_INTENSITY = 1.0
Expand Down
4 changes: 2 additions & 2 deletions examples/carla/Carla_Challenge/carlaChallenge9.scenic
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@
Based on 2019 Carla Challenge Traffic Scenario 09.
Ego-vehicle is performing a right turn at an intersection, yielding to crossing traffic.
"""
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
26 changes: 10 additions & 16 deletions src/scenic/domains/driving/simulators.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,37 +35,31 @@ def getLaneFollowingControllers(self, agent):
"""
dt = self.timestep
if agent.isCar:
lon_controller = PIDLongitudinalController(K_P=0.5, K_D=0.1, K_I=0.7, dt=dt)
lat_controller = PIDLateralController(K_P=0.2, K_D=0.1, K_I=0.0, dt=dt)
lon_controller = PIDLongitudinalController(K_P=1.0, K_D=0.2, K_I=1.4, dt=dt)
lat_controller = PIDLateralController(K_P=1.0, K_D=0.2, K_I=0.0, dt=dt)
else:
lon_controller = PIDLongitudinalController(
K_P=0.25, K_D=0.025, K_I=0.0, dt=dt
)
lat_controller = PIDLateralController(K_P=0.2, K_D=0.1, K_I=0.0, dt=dt)
lon_controller = PIDLongitudinalController(K_P=0.5, K_D=0.05, K_I=0.0, dt=dt)
lat_controller = PIDLateralController(K_P=1.0, K_D=0.2, K_I=0.0, dt=dt)
return lon_controller, lat_controller

def getTurningControllers(self, agent):
"""Get longitudinal and lateral controllers for turning."""
dt = self.timestep
if agent.isCar:
lon_controller = PIDLongitudinalController(K_P=0.5, K_D=0.1, K_I=0.7, dt=dt)
lat_controller = PIDLateralController(K_P=0.8, K_D=0.2, K_I=0.0, dt=dt)
lon_controller = PIDLongitudinalController(K_P=1.0, K_D=0.2, K_I=1.4, dt=dt)
lat_controller = PIDLateralController(K_P=2.0, K_D=0.2, K_I=0.0, dt=dt)
else:
lon_controller = PIDLongitudinalController(
K_P=0.25, K_D=0.025, K_I=0.0, dt=dt
)
lat_controller = PIDLateralController(K_P=0.4, K_D=0.1, K_I=0.0, dt=dt)
lon_controller = PIDLongitudinalController(K_P=0.5, K_D=0.05, K_I=0.0, dt=dt)
lat_controller = PIDLateralController(K_P=2.0, K_D=0.2, K_I=0.0, dt=dt)
return lon_controller, lat_controller

def getLaneChangingControllers(self, agent):
"""Get longitudinal and lateral controllers for lane changing."""
dt = self.timestep
if agent.isCar:
lon_controller = PIDLongitudinalController(K_P=0.5, K_D=0.1, K_I=0.7, dt=dt)
lon_controller = PIDLongitudinalController(K_P=1.0, K_D=0.2, K_I=1.4, dt=dt)
lat_controller = PIDLateralController(K_P=0.08, K_D=0.3, K_I=0.0, dt=dt)
else:
lon_controller = PIDLongitudinalController(
K_P=0.25, K_D=0.025, K_I=0.0, dt=dt
)
lon_controller = PIDLongitudinalController(K_P=0.5, K_D=0.05, K_I=0.0, dt=dt)
lat_controller = PIDLateralController(K_P=0.1, K_D=0.3, K_I=0.0, dt=dt)
return lon_controller, lat_controller
42 changes: 18 additions & 24 deletions src/scenic/simulators/carla/blueprints.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,24 +15,23 @@

#: blueprints for cars
carModels = [
"vehicle.audi.a2",
"vehicle.audi.etron",
"vehicle.audi.tt",
"vehicle.bmw.grandtourer",
"vehicle.chevrolet.impala",
"vehicle.citroen.c3",
"vehicle.dodge.charger_police",
"vehicle.jeep.wrangler_rubicon",
"vehicle.lincoln.mkz_2017",
"vehicle.mercedes.coupe",
"vehicle.mini.cooper_s",
"vehicle.ford.mustang",
"vehicle.nissan.micra",
"vehicle.nissan.patrol",
"vehicle.seat.leon",
"vehicle.tesla.model3",
"vehicle.toyota.prius",
"vehicle.volkswagen.t2",
'vehicle.taxi.ford',
'vehicle.dodgecop.charger',
'vehicle.fuso.mitsubishi',
'vehicle.carlacola.actros',
'vehicle.ue4.chevrolet.impala',
'vehicle.ue4.ford.mustang',
'vehicle.ue4.mercedes.ccc',
'vehicle.firetruck.actros',
'vehicle.ue4.bmw.grantourer',
'vehicle.ue4.ford.crown',
'vehicle.ue4.audi.tt',
'vehicle.dodge.charger',
'vehicle.sprinter.mercedes',
'vehicle.ambulance.ford',
'vehicle.nissan.patrol',
'vehicle.mini.cooper',
'vehicle.lincoln.mkz'
]

#: blueprints for bicycles
Expand All @@ -59,12 +58,7 @@

#: blueprints for trash cans
trashModels = [
"static.prop.trashcan01",
"static.prop.trashcan02",
"static.prop.trashcan03",
"static.prop.trashcan04",
"static.prop.trashcan05",
"static.prop.bin",
"static.prop.dumpster",
]

#: blueprints for traffic cones
Expand Down
2 changes: 1 addition & 1 deletion src/scenic/simulators/carla/simulator.py
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,7 @@ def setup(self):
self.cameraManager = visuals.CameraManager(self.world, egoActor, self.hud)
self.cameraManager._transform_index = camPosIndex
self.cameraManager.set_sensor(camIndex)
self.cameraManager.set_transform(self.camTransform)
# self.cameraManager.set_transform(self.camTransform)

self.world.tick() ## allowing manualgearshift to take effect # TODO still need this?

Expand Down

0 comments on commit 310226e

Please sign in to comment.