From 0832793a1b2895d2dc3699aa9d9a456daac9aad1 Mon Sep 17 00:00:00 2001
From: glopezdiest <58212725+glopezdiest@users.noreply.github.com>
Date: Tue, 31 Aug 2021 13:16:43 +0200
Subject: [PATCH] Update to CARLA 0.9.12
* Added compatibility with CARLA 0.9.12
---
CARLA_VER | 2 +-
Docs/CHANGELOG.md | 5 ++-
Docs/creating_new_scenario.md | 2 +-
README.md | 1 +
manual_control.py | 27 +++++++++++-
no_rendering_mode.py | 2 +-
scenario_runner.py | 14 +++---
srunner/examples/ChangeLane.xml | 4 +-
srunner/examples/ChangingWeather.xosc | 2 +-
srunner/examples/ControlLoss.xml | 30 ++++++-------
srunner/examples/CutIn.xml | 4 +-
srunner/examples/FollowLeadingVehicle.xml | 44 +++++++++----------
srunner/examples/FollowLeadingVehicle.xosc | 2 +-
srunner/examples/FreeRide.xml | 4 +-
srunner/examples/LaneChangeSimple.xosc | 2 +-
srunner/examples/LeadingVehicle.xml | 20 ++++-----
srunner/examples/NoSignalJunction.xml | 2 +-
srunner/examples/ObjectCrossing.xml | 36 +++++++--------
srunner/examples/OppositeDirection.xml | 8 ++--
srunner/examples/OscControllerExample.xosc | 2 +-
srunner/examples/RunningRedLight.xml | 10 ++---
.../examples/SignalizedJunctionLeftTurn.xml | 12 ++---
.../examples/SignalizedJunctionRightTurn.xml | 14 +++---
srunner/examples/VehicleTurning.xml | 32 +++++++-------
.../openscenario_configuration.py | 2 +-
.../scenariomanager/carla_data_provider.py | 3 +-
srunner/scenariomanager/scenario_manager.py | 13 +++---
.../scenarioatomics/atomic_behaviors.py | 13 ++----
.../atomic_trigger_conditions.py | 20 ++-------
srunner/scenarios/route_scenario.py | 4 +-
srunner/tools/route_manipulation.py | 5 +--
31 files changed, 176 insertions(+), 165 deletions(-)
diff --git a/CARLA_VER b/CARLA_VER
index ff9f1f726..c67dfe572 100644
--- a/CARLA_VER
+++ b/CARLA_VER
@@ -1,2 +1,2 @@
HOST = https://carla-releases.s3.eu-west-3.amazonaws.com/Linux
-RELEASE=CARLA_0.9.10
+RELEASE=CARLA_0.9.12
diff --git a/Docs/CHANGELOG.md b/Docs/CHANGELOG.md
index f304c8ddc..a342a1392 100644
--- a/Docs/CHANGELOG.md
+++ b/Docs/CHANGELOG.md
@@ -1,5 +1,6 @@
## Table of Contents
* [Latest Changes](#latest-changes)
+* [CARLA ScenarioRunner 0.9.12](#carla-scenariorunner-0912)
* [CARLA ScenarioRunner 0.9.11](#carla-scenariorunner-0911)
* [CARLA ScenarioRunner 0.9.10](#carla-scenariorunner-0910)
* [CARLA ScenarioRunner 0.9.9](#carla-scenariorunner-099)
@@ -10,7 +11,9 @@
* [CARLA ScenarioRunner 0.9.5](#carla-scenariorunner-095)
* [CARLA ScenarioRunner 0.9.2](#carla-scenariorunner-092)
-## Latest Changes
+## Latest changes
+
+## CARLA ScenarioRunner 0.9.12
### :rocket: New Features
* OpenSCENARIO support:
- Added support for LongitudinalDistanceAction
diff --git a/Docs/creating_new_scenario.md b/Docs/creating_new_scenario.md
index 62f12414f..3942af536 100644
--- a/Docs/creating_new_scenario.md
+++ b/Docs/creating_new_scenario.md
@@ -88,7 +88,7 @@ If you want to add multiple ego vehicles for a scenario, make sure that they use
role names, e.g.
```
-
+
```
diff --git a/README.md b/README.md
index a6631fe80..970de37d2 100644
--- a/README.md
+++ b/README.md
@@ -21,6 +21,7 @@ branch contains the latest fixes and features, and may be required to use the la
It is important to also consider the release version that has to match the CARLA version.
+* [Version 0.9.12](https://github.com/carla-simulator/scenario_runner/releases/tag/v0.9.12) and the 0.9.12 Branch: Compatible with [CARLA 0.9.12](https://github.com/carla-simulator/carla/releases/tag/0.9.12)
* [Version 0.9.11](https://github.com/carla-simulator/scenario_runner/releases/tag/v0.9.11) and the 0.9.11 Branch: Compatible with [CARLA 0.9.11](https://github.com/carla-simulator/carla/releases/tag/0.9.11)
* [Version 0.9.10](https://github.com/carla-simulator/scenario_runner/releases/tag/v0.9.10) and the 0.9.10 Branch: Compatible with [CARLA 0.9.10](https://github.com/carla-simulator/carla/releases/tag/0.9.10)
* [Version 0.9.9](https://github.com/carla-simulator/scenario_runner/releases/tag/v0.9.9) and the 0.9.9 Branch: Compatible with [CARLA 0.9.9](https://github.com/carla-simulator/carla/releases/tag/0.9.9). Use the 0.9.9 branch, if you use CARLA 0.9.9.4.
diff --git a/manual_control.py b/manual_control.py
index a8ba87d3a..201d9b194 100755
--- a/manual_control.py
+++ b/manual_control.py
@@ -119,6 +119,11 @@ def restart(self):
actor_type = get_actor_display_name(self.player)
self.hud.notification(actor_type)
+ if self.sync:
+ self.world.tick()
+ else:
+ self.world.wait_for_tick()
+
def tick(self, clock):
if len(self.world.get_actors().filter(self.player_name)) < 1:
return False
@@ -150,7 +155,7 @@ def game_loop(args):
clock = pygame.time.Clock()
while True:
clock.tick_busy_loop(60)
- if controller.parse_events(client, world, clock):
+ if controller.parse_events(client, world, clock, args.sync):
return
if not world.tick(clock):
return
@@ -204,6 +209,25 @@ def main():
metavar='WIDTHxHEIGHT',
default='1280x720',
help='window resolution (default: 1280x720)')
+ argparser.add_argument(
+ '--generation',
+ metavar='G',
+ default='2',
+ help='restrict to certain actor generation (values: "1","2","All" - default: "2")')
+ argparser.add_argument(
+ '--gamma',
+ default=2.2,
+ type=float,
+ help='Gamma correction of the camera (default: 2.2)')
+ argparser.add_argument(
+ '-s', '--seed',
+ help='Set seed for repeating executions (default: None)',
+ default=None,
+ type=int)
+ argparser.add_argument(
+ '--sync',
+ action='store_true',
+ help='Activate synchronous mode execution')
argparser.add_argument(
'--rolename',
metavar='NAME',
@@ -216,7 +240,6 @@ def main():
args = argparser.parse_args()
args.filter = "vehicle.*" # Needed for CARLA version
- args.gamma = 2.2 # Needed for CARLA version
args.width, args.height = [int(x) for x in args.res.split('x')]
log_level = logging.DEBUG if args.debug else logging.INFO
diff --git a/no_rendering_mode.py b/no_rendering_mode.py
index e6f277ff8..ec24d1dab 100755
--- a/no_rendering_mode.py
+++ b/no_rendering_mode.py
@@ -954,7 +954,7 @@ def update_hud_info(self, clock):
'Server: % 16s FPS' % self.server_fps,
'Client: % 16s FPS' % round(clock.get_fps()),
'Simulation Time: % 12s' % datetime.timedelta(seconds=int(self.simulation_time)),
- 'Map Name: %10s' % self.town_map.name,
+ 'Map Name: %10s' % self.town_map.name.split('/')[-1],
]
module_info_text = module_info_text
diff --git a/scenario_runner.py b/scenario_runner.py
index f88545b87..dda3685a7 100755
--- a/scenario_runner.py
+++ b/scenario_runner.py
@@ -41,7 +41,7 @@
from srunner.tools.route_parser import RouteParser
# Version of scenario_runner
-VERSION = '0.9.11'
+VERSION = '0.9.12'
class ScenarioRunner(object):
@@ -89,11 +89,10 @@ def __init__(self, args):
# requests in the localhost at port 2000.
self.client = carla.Client(args.host, int(args.port))
self.client.set_timeout(self.client_timeout)
- CarlaDataProvider.set_client(self.client)
dist = pkg_resources.get_distribution("carla")
- if LooseVersion(dist.version) < LooseVersion('0.9.11'):
- raise ImportError("CARLA version 0.9.11 or newer required. CARLA version found: {}".format(dist))
+ if LooseVersion(dist.version) < LooseVersion('0.9.12'):
+ raise ImportError("CARLA version 0.9.12 or newer required. CARLA version found: {}".format(dist))
# Load agent if requested via command line args
# If something goes wrong an exception will be thrown by importlib (ok here)
@@ -330,6 +329,8 @@ def _load_and_wait_for_world(self, town, ego_vehicles=None):
settings.synchronous_mode = True
settings.fixed_delta_seconds = 1.0 / self.frame_rate
self.world.apply_settings(settings)
+
+ CarlaDataProvider.set_client(self.client)
CarlaDataProvider.set_world(self.world)
# Wait for the world to be ready
@@ -338,8 +339,9 @@ def _load_and_wait_for_world(self, town, ego_vehicles=None):
else:
self.world.wait_for_tick()
- if CarlaDataProvider.get_map().name != town and CarlaDataProvider.get_map().name != "OpenDriveMap":
- print("The CARLA server uses the wrong map: {}".format(CarlaDataProvider.get_map().name))
+ map_name = CarlaDataProvider.get_map().name.split('/')[-1]
+ if map_name not in (town, "OpenDriveMap"):
+ print("The CARLA server uses the wrong map: {}".format(map_name))
print("This scenario requires to use map: {}".format(town))
return False
diff --git a/srunner/examples/ChangeLane.xml b/srunner/examples/ChangeLane.xml
index d7f7760c2..d2641060e 100644
--- a/srunner/examples/ChangeLane.xml
+++ b/srunner/examples/ChangeLane.xml
@@ -1,13 +1,13 @@
-
+
-
+
diff --git a/srunner/examples/ChangingWeather.xosc b/srunner/examples/ChangingWeather.xosc
index c4cc3142f..38e0d5482 100644
--- a/srunner/examples/ChangingWeather.xosc
+++ b/srunner/examples/ChangingWeather.xosc
@@ -9,7 +9,7 @@
-
+
diff --git a/srunner/examples/ControlLoss.xml b/srunner/examples/ControlLoss.xml
index 032b3fc31..23e7b9b80 100644
--- a/srunner/examples/ControlLoss.xml
+++ b/srunner/examples/ControlLoss.xml
@@ -1,48 +1,48 @@
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
diff --git a/srunner/examples/CutIn.xml b/srunner/examples/CutIn.xml
index 1c249d731..696023b96 100644
--- a/srunner/examples/CutIn.xml
+++ b/srunner/examples/CutIn.xml
@@ -2,12 +2,12 @@
-
+
-
+
diff --git a/srunner/examples/FollowLeadingVehicle.xml b/srunner/examples/FollowLeadingVehicle.xml
index c74a802bc..611496e08 100644
--- a/srunner/examples/FollowLeadingVehicle.xml
+++ b/srunner/examples/FollowLeadingVehicle.xml
@@ -1,70 +1,70 @@
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
diff --git a/srunner/examples/FollowLeadingVehicle.xosc b/srunner/examples/FollowLeadingVehicle.xosc
index 3089f244a..cb91a6529 100644
--- a/srunner/examples/FollowLeadingVehicle.xosc
+++ b/srunner/examples/FollowLeadingVehicle.xosc
@@ -11,7 +11,7 @@
-
+
diff --git a/srunner/examples/FreeRide.xml b/srunner/examples/FreeRide.xml
index 9ad20fa8e..c042ae5fe 100644
--- a/srunner/examples/FreeRide.xml
+++ b/srunner/examples/FreeRide.xml
@@ -13,11 +13,11 @@
-
+
-
+
diff --git a/srunner/examples/LaneChangeSimple.xosc b/srunner/examples/LaneChangeSimple.xosc
index cceee23f1..62a6287ce 100644
--- a/srunner/examples/LaneChangeSimple.xosc
+++ b/srunner/examples/LaneChangeSimple.xosc
@@ -26,7 +26,7 @@
-
+
diff --git a/srunner/examples/LeadingVehicle.xml b/srunner/examples/LeadingVehicle.xml
index 043e76f53..1a8121067 100644
--- a/srunner/examples/LeadingVehicle.xml
+++ b/srunner/examples/LeadingVehicle.xml
@@ -1,33 +1,33 @@
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
diff --git a/srunner/examples/NoSignalJunction.xml b/srunner/examples/NoSignalJunction.xml
index ceae7ca2b..440730062 100644
--- a/srunner/examples/NoSignalJunction.xml
+++ b/srunner/examples/NoSignalJunction.xml
@@ -1,7 +1,7 @@
-
+
diff --git a/srunner/examples/ObjectCrossing.xml b/srunner/examples/ObjectCrossing.xml
index a5bfb7972..f255403df 100644
--- a/srunner/examples/ObjectCrossing.xml
+++ b/srunner/examples/ObjectCrossing.xml
@@ -1,58 +1,58 @@
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
diff --git a/srunner/examples/OppositeDirection.xml b/srunner/examples/OppositeDirection.xml
index 8c03237c1..ecd72441f 100644
--- a/srunner/examples/OppositeDirection.xml
+++ b/srunner/examples/OppositeDirection.xml
@@ -1,15 +1,15 @@
-
+
-
+
-
+
-
+
diff --git a/srunner/examples/OscControllerExample.xosc b/srunner/examples/OscControllerExample.xosc
index 993905f5a..e81cbd09a 100644
--- a/srunner/examples/OscControllerExample.xosc
+++ b/srunner/examples/OscControllerExample.xosc
@@ -9,7 +9,7 @@
-
+
diff --git a/srunner/examples/RunningRedLight.xml b/srunner/examples/RunningRedLight.xml
index f93156540..1b5c9d023 100644
--- a/srunner/examples/RunningRedLight.xml
+++ b/srunner/examples/RunningRedLight.xml
@@ -1,23 +1,23 @@
-
+
-
+
-
+
-
+
-
+
\ No newline at end of file
diff --git a/srunner/examples/SignalizedJunctionLeftTurn.xml b/srunner/examples/SignalizedJunctionLeftTurn.xml
index 9d1a9eab8..037a8e053 100644
--- a/srunner/examples/SignalizedJunctionLeftTurn.xml
+++ b/srunner/examples/SignalizedJunctionLeftTurn.xml
@@ -1,27 +1,27 @@
-
+
-
+
-
+
-
+
-
+
-
+
diff --git a/srunner/examples/SignalizedJunctionRightTurn.xml b/srunner/examples/SignalizedJunctionRightTurn.xml
index 31d9a44f1..291c3ddc5 100644
--- a/srunner/examples/SignalizedJunctionRightTurn.xml
+++ b/srunner/examples/SignalizedJunctionRightTurn.xml
@@ -1,31 +1,31 @@
-
+
-
+
-
+
-
+
-
+
-
+
-
+
diff --git a/srunner/examples/VehicleTurning.xml b/srunner/examples/VehicleTurning.xml
index 26076f99a..3160808e0 100644
--- a/srunner/examples/VehicleTurning.xml
+++ b/srunner/examples/VehicleTurning.xml
@@ -1,51 +1,51 @@
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
diff --git a/srunner/scenarioconfigs/openscenario_configuration.py b/srunner/scenarioconfigs/openscenario_configuration.py
index b0a209bd8..950fa1733 100644
--- a/srunner/scenarioconfigs/openscenario_configuration.py
+++ b/srunner/scenarioconfigs/openscenario_configuration.py
@@ -173,7 +173,7 @@ def _set_carla_town(self):
world.get_settings()
wmap = world.get_map()
- if world is None or (wmap is not None and wmap.name != self.town):
+ if world is None or (wmap is not None and wmap.name.split('/')[-1] != self.town):
if ".xodr" in self.town:
with open(self.town, 'r', encoding='utf-8') as od_file:
data = od_file.read()
diff --git a/srunner/scenariomanager/carla_data_provider.py b/srunner/scenariomanager/carla_data_provider.py
index 517f92981..25cae11df 100644
--- a/srunner/scenariomanager/carla_data_provider.py
+++ b/srunner/scenariomanager/carla_data_provider.py
@@ -606,7 +606,8 @@ def request_new_actors(actor_list, safe_blueprint=False, tick=True):
if blueprint.has_tag('walker'):
# On imported OpenDRIVE maps, spawning of pedestrians can fail.
# By increasing the z-value the chances of success are increased.
- if not CarlaDataProvider._map.name.startswith('OpenDrive'):
+ map_name = CarlaDataProvider._map.name.split("/")[-1]
+ if not map_name.startswith('OpenDrive'):
_spawn_point.location.z = transform.location.z + 0.2
else:
_spawn_point.location.z = transform.location.z + 0.8
diff --git a/srunner/scenariomanager/scenario_manager.py b/srunner/scenariomanager/scenario_manager.py
index 8194bc013..62cffabf1 100644
--- a/srunner/scenariomanager/scenario_manager.py
+++ b/srunner/scenariomanager/scenario_manager.py
@@ -55,11 +55,11 @@ def __init__(self, debug_mode=False, sync_mode=False, timeout=2.0):
self._debug_mode = debug_mode
self._agent = None
self._sync_mode = sync_mode
- self._running = False
- self._timestamp_last_run = 0.0
+ self._watchdog = None
self._timeout = timeout
- self._watchdog = Watchdog(float(self._timeout))
+ self._running = False
+ self._timestamp_last_run = 0.0
self.scenario_duration_system = 0.0
self.scenario_duration_game = 0.0
self.start_system_time = None
@@ -82,7 +82,9 @@ def cleanup(self):
This function triggers a proper termination of a scenario
"""
- self._watchdog.stop()
+ if self._watchdog is not None:
+ self._watchdog.stop()
+ self._watchdog = None
if self.scenario is not None:
self.scenario.terminate()
@@ -121,6 +123,7 @@ def run_scenario(self):
self.start_system_time = time.time()
start_game_time = GameTime.get_time()
+ self._watchdog = Watchdog(float(self._timeout))
self._watchdog.start()
self._running = True
@@ -134,8 +137,6 @@ def run_scenario(self):
if timestamp:
self._tick_scenario(timestamp)
- self._watchdog.stop()
-
self.cleanup()
self.end_system_time = time.time()
diff --git a/srunner/scenariomanager/scenarioatomics/atomic_behaviors.py b/srunner/scenariomanager/scenarioatomics/atomic_behaviors.py
index 480b64003..3b79a2f05 100644
--- a/srunner/scenariomanager/scenarioatomics/atomic_behaviors.py
+++ b/srunner/scenariomanager/scenarioatomics/atomic_behaviors.py
@@ -32,8 +32,7 @@
from agents.navigation.basic_agent import BasicAgent, LocalPlanner
from agents.navigation.local_planner import RoadOption
from agents.navigation.global_route_planner import GlobalRoutePlanner
-from agents.navigation.global_route_planner_dao import GlobalRoutePlannerDAO
-from agents.tools.misc import is_within_distance_ahead
+from agents.tools.misc import is_within_distance
from srunner.scenariomanager.carla_data_provider import CarlaDataProvider
from srunner.scenariomanager.actorcontrols.actor_control import ActorControl
@@ -758,9 +757,7 @@ def initialise(self):
# Obtain final route, considering the routing option
# At the moment everything besides "shortest" will use the CARLA GlobalPlanner
- dao = GlobalRoutePlannerDAO(CarlaDataProvider.get_world().get_map(), 2.0)
- grp = GlobalRoutePlanner(dao)
- grp.setup()
+ grp = GlobalRoutePlanner(CarlaDataProvider.get_world().get_map(), 2.0)
route = []
for i, _ in enumerate(carla_route_elements):
if carla_route_elements[i][1] == "shortest":
@@ -2872,9 +2869,7 @@ def initialise(self):
self._start_time = GameTime.get_time()
actor_dict[self._actor.id].update_target_speed(self.max_speed, start_time=self._start_time)
- dao = GlobalRoutePlannerDAO(CarlaDataProvider.get_world().get_map(), 1.0)
- self._global_rp = GlobalRoutePlanner(dao)
- self._global_rp.setup()
+ self._global_rp = GlobalRoutePlanner(CarlaDataProvider.get_world().get_map(), 1.0)
super(KeepLongitudinalGap, self).initialise()
@@ -2905,7 +2900,7 @@ def update(self):
global_planner=self._global_rp)
actor_transform = CarlaDataProvider.get_transform(self._actor)
ref_actor_transform = CarlaDataProvider.get_transform(self._reference_actor)
- if is_within_distance_ahead(ref_actor_transform, actor_transform, float('inf')) and \
+ if is_within_distance(ref_actor_transform, actor_transform, float('inf'), [0, 90]) and \
operator.le(gap, self._gap):
try:
factor = abs(actor_velocity - reference_velocity)/actor_velocity
diff --git a/srunner/scenariomanager/scenarioatomics/atomic_trigger_conditions.py b/srunner/scenariomanager/scenarioatomics/atomic_trigger_conditions.py
index 75deaf2b5..1ff47565f 100644
--- a/srunner/scenariomanager/scenarioatomics/atomic_trigger_conditions.py
+++ b/srunner/scenariomanager/scenarioatomics/atomic_trigger_conditions.py
@@ -27,7 +27,6 @@
import carla
from agents.navigation.global_route_planner import GlobalRoutePlanner
-from agents.navigation.global_route_planner_dao import GlobalRoutePlannerDAO
from srunner.scenariomanager.scenarioatomics.atomic_behaviors import calculate_distance
from srunner.scenariomanager.carla_data_provider import CarlaDataProvider
@@ -108,10 +107,7 @@ def __init__(self, actor, osc_position, distance, along_route=False,
if self._along_route:
# Get the global route planner, used to calculate the route
- dao = GlobalRoutePlannerDAO(self._map, 0.5)
- grp = GlobalRoutePlanner(dao)
- grp.setup()
- self._grp = grp
+ self._grp = GlobalRoutePlanner(self._map, 0.5)
else:
self._grp = None
@@ -176,10 +172,7 @@ def __init__(self, actor, osc_position, time, along_route=False,
if self._along_route:
# Get the global route planner, used to calculate the route
- dao = GlobalRoutePlannerDAO(self._map, 0.5)
- grp = GlobalRoutePlanner(dao)
- grp.setup()
- self._grp = grp
+ self._grp = GlobalRoutePlanner(self._map, 0.5)
else:
self._grp = None
@@ -593,9 +586,7 @@ def __init__(self, reference_actor, actor, distance, comparison_operator=operato
self._comparison_operator = comparison_operator
if distance_type == "longitudinal":
- dao = GlobalRoutePlannerDAO(CarlaDataProvider.get_world().get_map(), 1.0)
- self._global_rp = GlobalRoutePlanner(dao)
- self._global_rp.setup()
+ self._global_rp = GlobalRoutePlanner(CarlaDataProvider.get_world().get_map(), 1.0)
else:
self._global_rp = None
@@ -864,10 +855,7 @@ def __init__(self, actor, other_actor, time, condition_freespace=False,
if self._along_route:
# Get the global route planner, used to calculate the route
- dao = GlobalRoutePlannerDAO(self._map, 0.5)
- grp = GlobalRoutePlanner(dao)
- grp.setup()
- self._grp = grp
+ self._grp = GlobalRoutePlanner(self._map, 0.5)
else:
self._grp = None
diff --git a/srunner/scenarios/route_scenario.py b/srunner/scenarios/route_scenario.py
index 7a42cad05..753da811f 100644
--- a/srunner/scenarios/route_scenario.py
+++ b/srunner/scenarios/route_scenario.py
@@ -211,7 +211,7 @@ def _update_ego_vehicle(self):
elevate_transform = self.route[0][0]
elevate_transform.location.z += 0.5
- ego_vehicle = CarlaDataProvider.request_new_actor('vehicle.lincoln.mkz2017',
+ ego_vehicle = CarlaDataProvider.request_new_actor('vehicle.lincoln.mkz_2017',
elevate_transform,
rolename='hero')
@@ -332,7 +332,7 @@ def _build_scenario_instances(self, world, ego_vehicle, scenario_definitions,
scenario_configuration.other_actors = list_of_actor_conf_instances
scenario_configuration.trigger_points = [egoactor_trigger_position]
scenario_configuration.subtype = definition['scenario_type']
- scenario_configuration.ego_vehicles = [ActorConfigurationData('vehicle.lincoln.mkz2017',
+ scenario_configuration.ego_vehicles = [ActorConfigurationData('vehicle.lincoln.mkz_2017',
ego_vehicle.get_transform(),
'hero')]
route_var_name = "ScenarioRouteNumber{}".format(scenario_number)
diff --git a/srunner/tools/route_manipulation.py b/srunner/tools/route_manipulation.py
index 0fed0881b..af4349f88 100644
--- a/srunner/tools/route_manipulation.py
+++ b/srunner/tools/route_manipulation.py
@@ -14,7 +14,6 @@
import xml.etree.ElementTree as ET
from agents.navigation.global_route_planner import GlobalRoutePlanner
-from agents.navigation.global_route_planner_dao import GlobalRoutePlannerDAO
from agents.navigation.local_planner import RoadOption
@@ -139,9 +138,7 @@ def interpolate_trajectory(world, waypoints_trajectory, hop_resolution=1.0):
:return: the full interpolated route both in GPS coordinates and also in its original form.
"""
- dao = GlobalRoutePlannerDAO(world.get_map(), hop_resolution)
- grp = GlobalRoutePlanner(dao)
- grp.setup()
+ grp = GlobalRoutePlanner(world.get_map(), hop_resolution)
# Obtain route plan
route = []
for i in range(len(waypoints_trajectory) - 1): # Goes until the one before the last.