Merge branch 'master' into jenkins/opendrive
This commit is contained in:
commit
47119f9300
|
@ -28,6 +28,7 @@ Install
|
|||
*.workspace
|
||||
*CodeCompletionFolders.txt
|
||||
*CodeLitePreProcessor.txt
|
||||
.aria2c.input
|
||||
.codelite
|
||||
.gdb_history
|
||||
.gtest
|
||||
|
|
33
.travis.yml
33
.travis.yml
|
@ -2,7 +2,7 @@ language: cpp
|
|||
compiler: clang
|
||||
|
||||
os: linux
|
||||
dist: trusty
|
||||
dist: xenial
|
||||
sudo: false
|
||||
|
||||
matrix:
|
||||
|
@ -13,7 +13,6 @@ matrix:
|
|||
apt:
|
||||
sources:
|
||||
- ubuntu-toolchain-r-test
|
||||
- llvm-toolchain-trusty-6.0
|
||||
packages:
|
||||
- g++-7 # we need this one for the libstdc++.
|
||||
- clang-6.0
|
||||
|
@ -27,7 +26,8 @@ matrix:
|
|||
- libjpeg-dev
|
||||
install:
|
||||
- pip2 install -q --user setuptools nose2
|
||||
- pip3 install -q --user setuptools nose2
|
||||
- pip3 install -q --user setuptools
|
||||
- pip3 install -q --user nose2
|
||||
script:
|
||||
- while sleep 2m; do echo "still building..."; done &
|
||||
- make setup >> build.log 2>&1
|
||||
|
@ -38,6 +38,33 @@ matrix:
|
|||
after_failure:
|
||||
- tail --lines=2000 build.log
|
||||
|
||||
- env: TEST="Pylint 2"
|
||||
addons:
|
||||
apt:
|
||||
packages:
|
||||
- python
|
||||
- python-pip
|
||||
install:
|
||||
- pip2 install -q --user pylint
|
||||
- pip2 install -q --user -r PythonAPI/requirements.txt
|
||||
script:
|
||||
- shopt -s globstar
|
||||
- pylint --disable=R,C --rcfile=PythonAPI/.pylintrc PythonAPI/**/*.py
|
||||
|
||||
- env: TEST="Pylint 3"
|
||||
addons:
|
||||
apt:
|
||||
packages:
|
||||
- python3
|
||||
- python3-pip
|
||||
install:
|
||||
- pip3 install -q --user setuptools
|
||||
- pip3 install -q pylint
|
||||
- pip3 install -q --user -r PythonAPI/requirements.txt
|
||||
script:
|
||||
- shopt -s globstar
|
||||
- pylint --disable=R,C --rcfile=PythonAPI/.pylintrc PythonAPI/**/*.py
|
||||
|
||||
- env: TEST="MkDocs"
|
||||
install:
|
||||
- pip install -q --user mkdocs
|
||||
|
|
|
@ -1,5 +1,7 @@
|
|||
## Latest Changes
|
||||
* Adding a parser to represent the map as a connected graph of waypoints.
|
||||
|
||||
* Migrate Content to AWS
|
||||
* Adding a parser to represent the map as a connected graph of waypoints.
|
||||
* Allow user to disable rendering and set the server timeout from the command line
|
||||
* Add timestamp to SensorData
|
||||
* Allow usage of hostname for carla::Client and resolve them to IP address
|
||||
|
@ -7,6 +9,7 @@
|
|||
* Added `id` property to waypoints, uniquely identifying waypoints up to half centimetre precision
|
||||
* Added OpenDrive's road offset `s` as property to waypoints
|
||||
* Fixed python client DLL error on Windows
|
||||
* Fixed wheel's tire friction from physics control parameters.
|
||||
* Fixed cleanup of local_planner when used by other modules
|
||||
|
||||
## CARLA 0.9.4
|
||||
|
|
|
@ -14,7 +14,7 @@ Python
|
|||
* Comments should not exceed 80 columns, code should not exceed 120 columns.
|
||||
* All code must be compatible with Python 2.7, 3.5, and 3.6.
|
||||
* [Pylint][pylintlink] should not give any error or warning (few exceptions
|
||||
apply with external classes like `numpy`, see our `.pylintrc`).
|
||||
apply with external classes like `numpy` and `pygame`, see our `.pylintrc`).
|
||||
* Python code follows [PEP8 style guide][pep8link] (use `autopep8` whenever
|
||||
possible).
|
||||
|
||||
|
|
|
@ -0,0 +1,6 @@
|
|||
[MESSAGES CONTROL]
|
||||
max-line-length=120
|
||||
[MASTER]
|
||||
disable=I0011,I0013,E1121
|
||||
[TYPECHECK]
|
||||
ignored-modules=carla,carla.command,libcarla,pygame,numpy,configparser,ConfigParser
|
|
@ -15,6 +15,7 @@ from enum import Enum
|
|||
import carla
|
||||
from agents.tools.misc import is_within_distance_ahead, compute_magnitude_angle
|
||||
|
||||
|
||||
class AgentState(Enum):
|
||||
"""
|
||||
AGENT_STATE represents the possible states of a roaming agent
|
||||
|
@ -35,26 +36,28 @@ class Agent(object):
|
|||
:param vehicle: actor to apply to local planner logic onto
|
||||
"""
|
||||
self._vehicle = vehicle
|
||||
self._proximity_threshold = 10.0 # meters
|
||||
self._local_planner = None
|
||||
self._world = self._vehicle.get_world()
|
||||
self._map = self._vehicle.get_world().get_map()
|
||||
self._last_traffic_light = None
|
||||
|
||||
|
||||
def run_step(self, debug=False):
|
||||
"""
|
||||
Execute one step of navigation.
|
||||
:return: control
|
||||
"""
|
||||
control = carla.VehicleControl()
|
||||
control.steer = 0.0
|
||||
control.throttle = 0.0
|
||||
control.brake = 0.0
|
||||
control.hand_brake = False
|
||||
control.manual_gear_shift = False
|
||||
|
||||
if debug:
|
||||
control.steer = 0.0
|
||||
control.throttle = 0.0
|
||||
control.brake = 0.0
|
||||
control.hand_brake = False
|
||||
control.manual_gear_shift = False
|
||||
|
||||
return control
|
||||
|
||||
|
||||
def _is_light_red(self, lights_list):
|
||||
"""
|
||||
Method to check if there is a red light affecting us. This version of
|
||||
|
@ -89,14 +92,14 @@ class Agent(object):
|
|||
for traffic_light in lights_list:
|
||||
object_waypoint = self._map.get_waypoint(traffic_light.get_location())
|
||||
if object_waypoint.road_id != ego_vehicle_waypoint.road_id or \
|
||||
object_waypoint.lane_id != ego_vehicle_waypoint.lane_id:
|
||||
object_waypoint.lane_id != ego_vehicle_waypoint.lane_id:
|
||||
continue
|
||||
|
||||
loc = traffic_light.get_location()
|
||||
if is_within_distance_ahead(loc, ego_vehicle_location,
|
||||
self._vehicle.get_transform().rotation.yaw,
|
||||
self._proximity_threshold):
|
||||
if traffic_light.state == carla.libcarla.TrafficLightState.Red:
|
||||
if traffic_light.state == carla.TrafficLightState.Red:
|
||||
return (True, traffic_light)
|
||||
|
||||
return (False, None)
|
||||
|
@ -119,9 +122,8 @@ class Agent(object):
|
|||
# It is too late. Do not block the intersection! Keep going!
|
||||
return (False, None)
|
||||
|
||||
if self._local_planner._target_waypoint is not None:
|
||||
if self._local_planner._target_waypoint.is_intersection:
|
||||
potential_lights = []
|
||||
if self._local_planner.target_waypoint is not None:
|
||||
if self._local_planner.target_waypoint.is_intersection:
|
||||
min_angle = 180.0
|
||||
sel_magnitude = 0.0
|
||||
sel_traffic_light = None
|
||||
|
@ -137,12 +139,13 @@ class Agent(object):
|
|||
|
||||
if sel_traffic_light is not None:
|
||||
if debug:
|
||||
print('=== Magnitude = {} | Angle = {} | ID = {}'.format(sel_magnitude, min_angle, sel_traffic_light.id))
|
||||
print('=== Magnitude = {} | Angle = {} | ID = {}'.format(
|
||||
sel_magnitude, min_angle, sel_traffic_light.id))
|
||||
|
||||
if self._last_traffic_light is None:
|
||||
self._last_traffic_light = sel_traffic_light
|
||||
|
||||
if self._last_traffic_light.state == carla.libcarla.TrafficLightState.Red:
|
||||
if self._last_traffic_light.state == carla.TrafficLightState.Red:
|
||||
return (True, self._last_traffic_light)
|
||||
else:
|
||||
self._last_traffic_light = None
|
||||
|
@ -178,7 +181,7 @@ class Agent(object):
|
|||
# if the object is not in our lane it's not an obstacle
|
||||
target_vehicle_waypoint = self._map.get_waypoint(target_vehicle.get_location())
|
||||
if target_vehicle_waypoint.road_id != ego_vehicle_waypoint.road_id or \
|
||||
target_vehicle_waypoint.lane_id != ego_vehicle_waypoint.lane_id:
|
||||
target_vehicle_waypoint.lane_id != ego_vehicle_waypoint.lane_id:
|
||||
continue
|
||||
|
||||
loc = target_vehicle.get_location()
|
||||
|
@ -189,7 +192,6 @@ class Agent(object):
|
|||
|
||||
return (False, None)
|
||||
|
||||
|
||||
def emergency_stop(self):
|
||||
"""
|
||||
Send an emergency stop command to the vehicle
|
||||
|
|
|
@ -15,13 +15,14 @@ import math
|
|||
import numpy as np
|
||||
|
||||
import carla
|
||||
from agents.navigation.agent import *
|
||||
from agents.navigation.agent import Agent, AgentState
|
||||
from agents.navigation.local_planner import LocalPlanner
|
||||
from agents.navigation.local_planner import compute_connection, RoadOption
|
||||
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 vector
|
||||
|
||||
|
||||
class BasicAgent(Agent):
|
||||
"""
|
||||
BasicAgent implements a basic agent that navigates scenes to reach a given
|
||||
|
@ -35,9 +36,9 @@ class BasicAgent(Agent):
|
|||
"""
|
||||
super(BasicAgent, self).__init__(vehicle)
|
||||
|
||||
self._proximity_threshold = 10.0 # meters
|
||||
self._proximity_threshold = 10.0 # meters
|
||||
self._state = AgentState.NAVIGATING
|
||||
self._local_planner = LocalPlanner(self._vehicle, opt_dict={'target_speed' : target_speed})
|
||||
self._local_planner = LocalPlanner(self._vehicle, opt_dict={'target_speed': target_speed})
|
||||
self._hop_resolution = 2.0
|
||||
|
||||
# setting up global router
|
||||
|
@ -73,8 +74,10 @@ class BasicAgent(Agent):
|
|||
wp_choice = current_waypoint.next(self._hop_resolution)
|
||||
# Stop at destination
|
||||
if current_waypoint.transform.location.distance(
|
||||
end_waypoint.transform.location) < self._hop_resolution: break
|
||||
if action == RoadOption.VOID: break
|
||||
end_waypoint.transform.location) < self._hop_resolution:
|
||||
break
|
||||
if action == RoadOption.VOID:
|
||||
break
|
||||
|
||||
# Select appropriate path at the junction
|
||||
if len(wp_choice) > 1:
|
||||
|
@ -105,7 +108,7 @@ class BasicAgent(Agent):
|
|||
if direction == 0:
|
||||
cross = abs(np.cross(v_current, v_select)[-1])
|
||||
else:
|
||||
cross = direction*np.cross(v_current, v_select)[-1]
|
||||
cross = direction * np.cross(v_current, v_select)[-1]
|
||||
if cross < select_criteria:
|
||||
select_criteria = cross
|
||||
current_waypoint = wp_select
|
||||
|
|
|
@ -14,7 +14,8 @@ import math
|
|||
import numpy as np
|
||||
|
||||
import carla
|
||||
from agents.tools.misc import distance_vehicle, get_speed
|
||||
from agents.tools.misc import get_speed
|
||||
|
||||
|
||||
class VehiclePIDController():
|
||||
"""
|
||||
|
@ -22,9 +23,7 @@ class VehiclePIDController():
|
|||
low level control a vehicle from client side
|
||||
"""
|
||||
|
||||
def __init__(self, vehicle,
|
||||
args_lateral={'K_P': 1.0, 'K_D': 0.0, 'K_I': 0.0},
|
||||
args_longitudinal={'K_P': 1.0, 'K_D': 0.0, 'K_I': 0.0}):
|
||||
def __init__(self, vehicle, args_lateral=None, args_longitudinal=None):
|
||||
"""
|
||||
:param vehicle: actor to apply to local planner logic onto
|
||||
:param args_lateral: dictionary of arguments to set the lateral PID controller using the following semantics:
|
||||
|
@ -37,12 +36,15 @@ class VehiclePIDController():
|
|||
K_D -- Differential term
|
||||
K_I -- Integral term
|
||||
"""
|
||||
if not args_lateral:
|
||||
args_lateral = {'K_P': 1.0, 'K_D': 0.0, 'K_I': 0.0}
|
||||
if not args_longitudinal:
|
||||
args_longitudinal = {'K_P': 1.0, 'K_D': 0.0, 'K_I': 0.0}
|
||||
|
||||
self._vehicle = vehicle
|
||||
self._world = self._vehicle.get_world()
|
||||
self._lon_controller = PIDLongitudinalController(
|
||||
self._vehicle, **args_longitudinal)
|
||||
self._lat_controller = PIDLateralController(
|
||||
self._vehicle, **args_lateral)
|
||||
self._lon_controller = PIDLongitudinalController(self._vehicle, **args_longitudinal)
|
||||
self._lat_controller = PIDLateralController(self._vehicle, **args_lateral)
|
||||
|
||||
def run_step(self, target_speed, waypoint):
|
||||
"""
|
||||
|
@ -169,7 +171,7 @@ class PIDLateralController():
|
|||
v_begin.x, waypoint.transform.location.y -
|
||||
v_begin.y, 0.0])
|
||||
_dot = math.acos(np.clip(np.dot(w_vec, v_vec) /
|
||||
(np.linalg.norm(w_vec) * np.linalg.norm(v_vec)), -1.0, 1.0))
|
||||
(np.linalg.norm(w_vec) * np.linalg.norm(v_vec)), -1.0, 1.0))
|
||||
|
||||
_cross = np.cross(v_vec, w_vec)
|
||||
if _cross[2] < 0:
|
||||
|
|
|
@ -6,12 +6,10 @@ This module provides GlobalRoutePlanner implementation.
|
|||
"""
|
||||
|
||||
import math
|
||||
from enum import Enum
|
||||
|
||||
import numpy as np
|
||||
import networkx as nx
|
||||
|
||||
import carla
|
||||
from agents.navigation.local_planner import RoadOption
|
||||
|
||||
|
||||
|
@ -65,17 +63,17 @@ class GlobalRoutePlanner(object):
|
|||
num_edges = 0
|
||||
cross_list = []
|
||||
# Accumulating cross products of all other paths
|
||||
for neighbor in self._graph.neighbors(route[i+1]):
|
||||
num_edges+=1
|
||||
for neighbor in self._graph.neighbors(route[i + 1]):
|
||||
num_edges += 1
|
||||
if neighbor != route[i + 2]:
|
||||
select_edge = self._graph.edges[route[i+1], neighbor]
|
||||
select_edge = self._graph.edges[route[i + 1], neighbor]
|
||||
sv = select_edge['net_vector']
|
||||
cross_list.append(np.cross(cv, sv)[2])
|
||||
# Calculating turn decision
|
||||
if next_edge['intersection'] and num_edges > 1:
|
||||
next_cross = np.cross(cv, nv)[2]
|
||||
deviation = math.acos(np.dot(cv, nv) /\
|
||||
(np.linalg.norm(cv)*np.linalg.norm(nv)))
|
||||
deviation = math.acos(np.dot(cv, nv) /
|
||||
(np.linalg.norm(cv) * np.linalg.norm(nv)))
|
||||
if deviation < threshold:
|
||||
action = RoadOption.STRAIGHT
|
||||
elif next_cross < min(cross_list):
|
||||
|
@ -222,5 +220,3 @@ class GlobalRoutePlanner(object):
|
|||
return : dot porduct scalar between vector1 and vector2
|
||||
"""
|
||||
return vector1[0] * vector2[0] + vector1[1] * vector2[1]
|
||||
|
||||
pass
|
||||
|
|
|
@ -5,8 +5,6 @@
|
|||
This module provides implementation for GlobalRoutePlannerDAO
|
||||
"""
|
||||
|
||||
import carla
|
||||
|
||||
|
||||
class GlobalRoutePlannerDAO(object):
|
||||
"""
|
||||
|
|
|
@ -16,6 +16,7 @@ import carla
|
|||
from agents.navigation.controller import VehiclePIDController
|
||||
from agents.tools.misc import distance_vehicle, draw_waypoints
|
||||
|
||||
|
||||
class RoadOption(Enum):
|
||||
"""
|
||||
RoadOption represents the possible topological configurations when moving from a segment of lane to other.
|
||||
|
@ -40,7 +41,7 @@ class LocalPlanner(object):
|
|||
# total distance)
|
||||
MIN_DISTANCE_PERCENTAGE = 0.9
|
||||
|
||||
def __init__(self, vehicle, opt_dict={}):
|
||||
def __init__(self, vehicle, opt_dict=None):
|
||||
"""
|
||||
:param vehicle: actor to apply to local planner logic onto
|
||||
:param opt_dict: dictionary of arguments with the following semantics:
|
||||
|
@ -60,20 +61,20 @@ class LocalPlanner(object):
|
|||
self._vehicle = vehicle
|
||||
self._map = self._vehicle.get_world().get_map()
|
||||
|
||||
self._dt = None
|
||||
self._target_speed = None
|
||||
self._sampling_radius = None
|
||||
self._min_distance = None
|
||||
self._current_waypoint = None
|
||||
self._target_road_option = None
|
||||
self._next_waypoints = None
|
||||
self._target_waypoint = None
|
||||
self._vehicle_controller = None
|
||||
self._global_plan = None
|
||||
# queue with tuples of (waypoint, RoadOption)
|
||||
self._waypoints_queue = deque(maxlen=600)
|
||||
self._buffer_size = 5
|
||||
self._waypoint_buffer = deque(maxlen=self._buffer_size)
|
||||
self.dt = None
|
||||
self.target_speed = None
|
||||
self.sampling_radius = None
|
||||
self.min_distance = None
|
||||
self.current_waypoint = None
|
||||
self.target_road_option = None
|
||||
self.next_waypoints = None
|
||||
self.target_waypoint = None
|
||||
self.vehicle_controller = None
|
||||
self.global_plan = None
|
||||
# queue with tuples of (waypoint, RoadOption)
|
||||
self.waypoints_queue = deque(maxlen=600)
|
||||
self.waypoint_buffer = deque(maxlen=self._buffer_size)
|
||||
|
||||
# initializing controller
|
||||
self.init_controller(opt_dict)
|
||||
|
@ -83,7 +84,6 @@ class LocalPlanner(object):
|
|||
self._vehicle.destroy()
|
||||
print("Destroying ego-vehicle!")
|
||||
|
||||
|
||||
def reset_vehicle(self):
|
||||
self._vehicle = None
|
||||
print("Resetting ego-vehicle!")
|
||||
|
@ -96,49 +96,49 @@ class LocalPlanner(object):
|
|||
:return:
|
||||
"""
|
||||
# default params
|
||||
self._dt = 1.0 / 20.0
|
||||
self._target_speed = 20.0 # Km/h
|
||||
self._sampling_radius = self._target_speed * 0.5 / 3.6 # 0.5 seconds horizon
|
||||
self._min_distance = self._sampling_radius * self.MIN_DISTANCE_PERCENTAGE
|
||||
self.dt = 1.0 / 20.0
|
||||
self.target_speed = 20.0 # Km/h
|
||||
self.sampling_radius = self.target_speed * 0.5 / 3.6 # 0.5 seconds horizon
|
||||
self.min_distance = self.sampling_radius * self.MIN_DISTANCE_PERCENTAGE
|
||||
args_lateral_dict = {
|
||||
'K_P': 1.95,
|
||||
'K_D': 0.01,
|
||||
'K_I': 1.4,
|
||||
'dt': self._dt}
|
||||
'dt': self.dt}
|
||||
args_longitudinal_dict = {
|
||||
'K_P': 1.0,
|
||||
'K_D': 0,
|
||||
'K_I': 1,
|
||||
'dt': self._dt}
|
||||
'dt': self.dt}
|
||||
|
||||
# parameters overload
|
||||
if 'dt' in opt_dict:
|
||||
self._dt = opt_dict['dt']
|
||||
if 'target_speed' in opt_dict:
|
||||
self._target_speed = opt_dict['target_speed']
|
||||
if 'sampling_radius' in opt_dict:
|
||||
self._sampling_radius = self._target_speed * \
|
||||
opt_dict['sampling_radius'] / 3.6
|
||||
if 'lateral_control_dict' in opt_dict:
|
||||
args_lateral_dict = opt_dict['lateral_control_dict']
|
||||
if 'longitudinal_control_dict' in opt_dict:
|
||||
args_longitudinal_dict = opt_dict['longitudinal_control_dict']
|
||||
if opt_dict:
|
||||
if 'dt' in opt_dict:
|
||||
self.dt = opt_dict['dt']
|
||||
if 'target_speed' in opt_dict:
|
||||
self.target_speed = opt_dict['target_speed']
|
||||
if 'sampling_radius' in opt_dict:
|
||||
self.sampling_radius = self.target_speed * \
|
||||
opt_dict['sampling_radius'] / 3.6
|
||||
if 'lateral_control_dict' in opt_dict:
|
||||
args_lateral_dict = opt_dict['lateral_control_dict']
|
||||
if 'longitudinal_control_dict' in opt_dict:
|
||||
args_longitudinal_dict = opt_dict['longitudinal_control_dict']
|
||||
|
||||
self._current_waypoint = self._map.get_waypoint(
|
||||
self._vehicle.get_location())
|
||||
self._vehicle_controller = VehiclePIDController(self._vehicle,
|
||||
args_lateral=args_lateral_dict,
|
||||
args_longitudinal=args_longitudinal_dict)
|
||||
self.current_waypoint = self._map.get_waypoint(self._vehicle.get_location())
|
||||
self.vehicle_controller = VehiclePIDController(self._vehicle,
|
||||
args_lateral=args_lateral_dict,
|
||||
args_longitudinal=args_longitudinal_dict)
|
||||
|
||||
self._global_plan = False
|
||||
self.global_plan = False
|
||||
|
||||
# compute initial waypoints
|
||||
self._waypoints_queue.append( (self._current_waypoint.next(self._sampling_radius)[0], RoadOption.LANEFOLLOW))
|
||||
self._target_road_option = RoadOption.LANEFOLLOW
|
||||
self.waypoints_queue.append((self.current_waypoint.next(self.sampling_radius)[0], RoadOption.LANEFOLLOW))
|
||||
|
||||
self.target_road_option = RoadOption.LANEFOLLOW
|
||||
# fill waypoint trajectory queue
|
||||
self._compute_next_waypoints(k=200)
|
||||
|
||||
|
||||
def set_speed(self, speed):
|
||||
"""
|
||||
Request new target speed.
|
||||
|
@ -146,7 +146,7 @@ class LocalPlanner(object):
|
|||
:param speed: new target speed in Km/h
|
||||
:return:
|
||||
"""
|
||||
self._target_speed = speed
|
||||
self.target_speed = speed
|
||||
|
||||
def _compute_next_waypoints(self, k=1):
|
||||
"""
|
||||
|
@ -156,12 +156,12 @@ class LocalPlanner(object):
|
|||
:return:
|
||||
"""
|
||||
# check we do not overflow the queue
|
||||
available_entries = self._waypoints_queue.maxlen - len(self._waypoints_queue)
|
||||
available_entries = self.waypoints_queue.maxlen - len(self.waypoints_queue)
|
||||
k = min(available_entries, k)
|
||||
|
||||
for _ in range(k):
|
||||
last_waypoint = self._waypoints_queue[-1][0]
|
||||
next_waypoints = list(last_waypoint.next(self._sampling_radius))
|
||||
last_waypoint = self.waypoints_queue[-1][0]
|
||||
next_waypoints = list(last_waypoint.next(self.sampling_radius))
|
||||
|
||||
if len(next_waypoints) == 1:
|
||||
# only one option available ==> lanefollowing
|
||||
|
@ -175,15 +175,14 @@ class LocalPlanner(object):
|
|||
next_waypoint = next_waypoints[road_options_list.index(
|
||||
road_option)]
|
||||
|
||||
self._waypoints_queue.append((next_waypoint, road_option))
|
||||
|
||||
self.waypoints_queue.append((next_waypoint, road_option))
|
||||
|
||||
def set_global_plan(self, current_plan):
|
||||
self._waypoints_queue.clear()
|
||||
self.waypoints_queue.clear()
|
||||
for elem in current_plan:
|
||||
self._waypoints_queue.append(elem)
|
||||
self._target_road_option = RoadOption.LANEFOLLOW
|
||||
self._global_plan = True
|
||||
self.waypoints_queue.append(elem)
|
||||
self.target_road_option = RoadOption.LANEFOLLOW
|
||||
self.global_plan = True
|
||||
|
||||
def run_step(self, debug=True):
|
||||
"""
|
||||
|
@ -195,11 +194,11 @@ class LocalPlanner(object):
|
|||
"""
|
||||
|
||||
# not enough waypoints in the horizon? => add more!
|
||||
if len(self._waypoints_queue) < int(self._waypoints_queue.maxlen * 0.5):
|
||||
if not self._global_plan:
|
||||
if len(self.waypoints_queue) < int(self.waypoints_queue.maxlen * 0.5):
|
||||
if not self.global_plan:
|
||||
self._compute_next_waypoints(k=100)
|
||||
|
||||
if len(self._waypoints_queue) == 0:
|
||||
if len(self.waypoints_queue) == 0:
|
||||
control = carla.VehicleControl()
|
||||
control.steer = 0.0
|
||||
control.throttle = 0.0
|
||||
|
@ -210,35 +209,35 @@ class LocalPlanner(object):
|
|||
return control
|
||||
|
||||
# Buffering the waypoints
|
||||
if not self._waypoint_buffer:
|
||||
if not self.waypoint_buffer:
|
||||
for i in range(self._buffer_size):
|
||||
if self._waypoints_queue:
|
||||
self._waypoint_buffer.append(
|
||||
self._waypoints_queue.popleft())
|
||||
if self.waypoints_queue:
|
||||
self.waypoint_buffer.append(
|
||||
self.waypoints_queue.popleft())
|
||||
else:
|
||||
break
|
||||
|
||||
# current vehicle waypoint
|
||||
self._current_waypoint = self._map.get_waypoint(self._vehicle.get_location())
|
||||
self.current_waypoint = self._map.get_waypoint(self._vehicle.get_location())
|
||||
# target waypoint
|
||||
self._target_waypoint, self._target_road_option = self._waypoint_buffer[0]
|
||||
self.target_waypoint, self.target_road_option = self.waypoint_buffer[0]
|
||||
# move using PID controllers
|
||||
control = self._vehicle_controller.run_step(self._target_speed, self._target_waypoint)
|
||||
control = self.vehicle_controller.run_step(self.target_speed, self.target_waypoint)
|
||||
|
||||
# purge the queue of obsolete waypoints
|
||||
vehicle_transform = self._vehicle.get_transform()
|
||||
max_index = -1
|
||||
|
||||
for i, (waypoint, _) in enumerate(self._waypoint_buffer):
|
||||
for i, (waypoint, _) in enumerate(self.waypoint_buffer):
|
||||
if distance_vehicle(
|
||||
waypoint, vehicle_transform) < self._min_distance:
|
||||
waypoint, vehicle_transform) < self.min_distance:
|
||||
max_index = i
|
||||
if max_index >= 0:
|
||||
for i in range(max_index + 1):
|
||||
self._waypoint_buffer.popleft()
|
||||
self.waypoint_buffer.popleft()
|
||||
|
||||
if debug:
|
||||
draw_waypoints(self._vehicle.get_world(), [self._target_waypoint], self._vehicle.get_location().z + 1.0)
|
||||
draw_waypoints(self._vehicle.get_world(), [self.target_waypoint], self._vehicle.get_location().z + 1.0)
|
||||
|
||||
return control
|
||||
|
||||
|
|
|
@ -9,10 +9,7 @@
|
|||
""" This module implements an agent that roams around a track following random waypoints and avoiding other vehicles.
|
||||
The agent also responds to traffic lights. """
|
||||
|
||||
from enum import Enum
|
||||
|
||||
import carla
|
||||
from agents.navigation.agent import *
|
||||
from agents.navigation.agent import Agent, AgentState
|
||||
from agents.navigation.local_planner import LocalPlanner
|
||||
|
||||
|
||||
|
|
|
@ -1,101 +0,0 @@
|
|||
import math
|
||||
import unittest
|
||||
|
||||
import carla
|
||||
|
||||
from global_route_planner import GlobalRoutePlanner
|
||||
from global_route_planner import NavEnum
|
||||
from global_route_planner_dao import GlobalRoutePlannerDAO
|
||||
|
||||
|
||||
class Test_GlobalRoutePlanner(unittest.TestCase):
|
||||
"""
|
||||
Test class for GlobalRoutePlanner class
|
||||
"""
|
||||
|
||||
def setUp(self):
|
||||
# == Utilities test instance without DAO == #
|
||||
self.simple_grp = GlobalRoutePlanner(None)
|
||||
|
||||
# == Integration test instance == #
|
||||
client = carla.Client('localhost', 2000)
|
||||
world = client.get_world()
|
||||
integ_dao = GlobalRoutePlannerDAO(world.get_map())
|
||||
self.integ_grp = GlobalRoutePlanner(integ_dao)
|
||||
self.integ_grp.setup()
|
||||
pass
|
||||
|
||||
def tearDown(self):
|
||||
self.simple_grp = None
|
||||
self.dao_grp = None
|
||||
self.integ_grp = None
|
||||
pass
|
||||
|
||||
def test_plan_route(self):
|
||||
"""
|
||||
Test for GlobalROutePlanner.plan_route()
|
||||
Run this test with carla server running Town03
|
||||
"""
|
||||
plan = self.integ_grp.plan_route((-60, -5), (-77.65, 72.72))
|
||||
self.assertEqual(
|
||||
plan, [NavEnum.START, NavEnum.LEFT, NavEnum.LEFT,
|
||||
NavEnum.GO_STRAIGHT, NavEnum.LEFT, NavEnum.STOP])
|
||||
|
||||
def test_path_search(self):
|
||||
"""
|
||||
Test for GlobalRoutePlanner.path_search()
|
||||
Run this test with carla server running Town03
|
||||
"""
|
||||
self.integ_grp.path_search((191.947, -5.602), (78.730, -50.091))
|
||||
self.assertEqual(
|
||||
self.integ_grp.path_search((196.947, -5.602), (78.730, -50.091)),
|
||||
[256, 157, 158, 117, 118, 59, 55, 230])
|
||||
|
||||
def test_localise(self):
|
||||
"""
|
||||
Test for GlobalRoutePlanner.localise()
|
||||
Run this test with carla server running Town03
|
||||
"""
|
||||
x, y = (200, -250)
|
||||
segment = self.integ_grp.localise(x, y)
|
||||
self.assertEqual(self.integ_grp._id_map[segment['entry']], 5)
|
||||
self.assertEqual(self.integ_grp._id_map[segment['exit']], 225)
|
||||
|
||||
def test_unit_vector(self):
|
||||
"""
|
||||
Test for GlobalROutePlanner.unit_vector()
|
||||
"""
|
||||
vector = self.simple_grp.unit_vector((1, 1), (2, 2))
|
||||
self.assertAlmostEquals(vector[0], 1 / math.sqrt(2))
|
||||
self.assertAlmostEquals(vector[1], 1 / math.sqrt(2))
|
||||
|
||||
def test_dot(self):
|
||||
"""
|
||||
Test for GlobalROutePlanner.test_dot()
|
||||
"""
|
||||
self.assertAlmostEqual(self.simple_grp.dot((1, 0), (0, 1)), 0)
|
||||
self.assertAlmostEqual(self.simple_grp.dot((1, 0), (1, 0)), 1)
|
||||
|
||||
|
||||
def suite():
|
||||
"""
|
||||
Gathering all tests
|
||||
"""
|
||||
|
||||
suite = unittest.TestSuite()
|
||||
suite.addTest(Test_GlobalRoutePlanner('test_unit_vector'))
|
||||
suite.addTest(Test_GlobalRoutePlanner('test_dot'))
|
||||
suite.addTest(Test_GlobalRoutePlanner('test_localise'))
|
||||
suite.addTest(Test_GlobalRoutePlanner('test_path_search'))
|
||||
suite.addTest(Test_GlobalRoutePlanner('test_plan_route'))
|
||||
|
||||
return suite
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
"""
|
||||
Running test suite
|
||||
"""
|
||||
mySuit = suite()
|
||||
runner = unittest.TextTestRunner()
|
||||
runner.run(mySuit)
|
|
@ -89,14 +89,15 @@ def distance_vehicle(waypoint, vehicle_transform):
|
|||
|
||||
return math.sqrt(dx * dx + dy * dy)
|
||||
|
||||
def vector(location_1, location_2):
|
||||
"""
|
||||
Returns the unit vector from location_1 to location_2
|
||||
location_1, location_2 : carla.Location objects
|
||||
"""
|
||||
x = location_2.x - location_1.x
|
||||
y = location_2.y - location_1.y
|
||||
z = location_2.z - location_1.z
|
||||
norm = np.linalg.norm([x, y, z])
|
||||
|
||||
return [x/norm, y/norm, z/norm]
|
||||
def vector(location_1, location_2):
|
||||
"""
|
||||
Returns the unit vector from location_1 to location_2
|
||||
location_1, location_2: carla.Location objects
|
||||
"""
|
||||
x = location_2.x - location_1.x
|
||||
y = location_2.y - location_1.y
|
||||
z = location_2.z - location_1.z
|
||||
norm = np.linalg.norm([x, y, z])
|
||||
|
||||
return [x / norm, y / norm, z / norm]
|
||||
|
|
|
@ -53,6 +53,8 @@ try:
|
|||
from pygame.locals import K_r
|
||||
from pygame.locals import K_s
|
||||
from pygame.locals import K_w
|
||||
from pygame.locals import K_MINUS
|
||||
from pygame.locals import K_EQUALS
|
||||
except ImportError:
|
||||
raise RuntimeError('cannot import pygame, make sure pygame package is installed')
|
||||
|
||||
|
@ -83,9 +85,8 @@ except IndexError:
|
|||
|
||||
import carla
|
||||
from carla import ColorConverter as cc
|
||||
from agents.navigation.roaming_agent import *
|
||||
from agents.navigation.basic_agent import *
|
||||
|
||||
from agents.navigation.roaming_agent import RoamingAgent
|
||||
from agents.navigation.basic_agent import BasicAgent
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
|
@ -101,7 +102,7 @@ def find_weather_presets():
|
|||
|
||||
def get_actor_display_name(actor, truncate=250):
|
||||
name = ' '.join(actor.type_id.replace('_', '.').title().split('.')[1:])
|
||||
return (name[:truncate-1] + u'\u2026') if len(name) > truncate else name
|
||||
return (name[:truncate - 1] + u'\u2026') if len(name) > truncate else name
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
|
@ -109,54 +110,53 @@ def get_actor_display_name(actor, truncate=250):
|
|||
# ==============================================================================
|
||||
|
||||
class World(object):
|
||||
def __init__(self, carla_world, hud):
|
||||
def __init__(self, carla_world, hud, actor_filter):
|
||||
self.world = carla_world
|
||||
self.map = self.world.get_map()
|
||||
self.hud = hud
|
||||
self.vehicle = None
|
||||
self.player = None
|
||||
self.collision_sensor = None
|
||||
self.lane_invasion_sensor = None
|
||||
self.gnss_sensor = None
|
||||
self.camera_manager = None
|
||||
self._weather_presets = find_weather_presets()
|
||||
self._weather_index = 0
|
||||
self._actor_filter = actor_filter
|
||||
self.restart()
|
||||
self.world.on_tick(hud.on_world_tick)
|
||||
self.recording_enabled = False
|
||||
self.recording_start = 0
|
||||
|
||||
def restart(self):
|
||||
# Keep same camera config if the camera manager exists.
|
||||
cam_index = self.camera_manager._index if self.camera_manager is not None else 0
|
||||
cam_pos_index = self.camera_manager._transform_index if self.camera_manager is not None else 0
|
||||
|
||||
blueprint = self.world.get_blueprint_library().find('vehicle.lincoln.mkz2017')
|
||||
cam_index = self.camera_manager.index if self.camera_manager is not None else 0
|
||||
cam_pos_index = self.camera_manager.transform_index if self.camera_manager is not None else 0
|
||||
# Get a random blueprint.
|
||||
blueprint = random.choice(self.world.get_blueprint_library().filter(self._actor_filter))
|
||||
blueprint.set_attribute('role_name', 'hero')
|
||||
if blueprint.has_attribute('color'):
|
||||
color = random.choice(blueprint.get_attribute('color').recommended_values)
|
||||
blueprint.set_attribute('color', color)
|
||||
|
||||
# Spawn the vehicle.
|
||||
if self.vehicle is not None:
|
||||
spawn_point = self.vehicle.get_transform()
|
||||
# Spawn the player.
|
||||
if self.player is not None:
|
||||
spawn_point = self.player.get_transform()
|
||||
spawn_point.location.z += 2.0
|
||||
spawn_point.rotation.roll = 0.0
|
||||
spawn_point.rotation.pitch = 0.0
|
||||
self.destroy()
|
||||
|
||||
self.player = self.world.try_spawn_actor(blueprint, spawn_point)
|
||||
while self.player is None:
|
||||
spawn_points = self.map.get_spawn_points()
|
||||
spawn_point = spawn_points[1]
|
||||
self.vehicle = self.world.spawn_actor(blueprint, spawn_point)
|
||||
|
||||
while self.vehicle is None:
|
||||
spawn_points = self.map.get_spawn_points()
|
||||
spawn_point = spawn_points[1]
|
||||
self.vehicle = self.world.spawn_actor(blueprint, spawn_point)
|
||||
|
||||
spawn_point = random.choice(spawn_points) if spawn_points else carla.Transform()
|
||||
self.player = self.world.try_spawn_actor(blueprint, spawn_point)
|
||||
# Set up the sensors.
|
||||
self.collision_sensor = CollisionSensor(self.vehicle, self.hud)
|
||||
self.lane_invasion_sensor = LaneInvasionSensor(self.vehicle, self.hud)
|
||||
self.camera_manager = CameraManager(self.vehicle, self.hud)
|
||||
self.camera_manager._transform_index = cam_pos_index
|
||||
self.collision_sensor = CollisionSensor(self.player, self.hud)
|
||||
self.lane_invasion_sensor = LaneInvasionSensor(self.player, self.hud)
|
||||
self.gnss_sensor = GnssSensor(self.player)
|
||||
self.camera_manager = CameraManager(self.player, self.hud)
|
||||
self.camera_manager.transform_index = cam_pos_index
|
||||
self.camera_manager.set_sensor(cam_index, notify=False)
|
||||
actor_type = get_actor_display_name(self.vehicle)
|
||||
actor_type = get_actor_display_name(self.player)
|
||||
self.hud.notification(actor_type)
|
||||
|
||||
def next_weather(self, reverse=False):
|
||||
|
@ -164,7 +164,7 @@ class World(object):
|
|||
self._weather_index %= len(self._weather_presets)
|
||||
preset = self._weather_presets[self._weather_index]
|
||||
self.hud.notification('Weather: %s' % preset[1])
|
||||
self.vehicle.get_world().set_weather(preset[0])
|
||||
self.player.get_world().set_weather(preset[0])
|
||||
|
||||
def tick(self, clock):
|
||||
self.hud.tick(self, clock)
|
||||
|
@ -173,30 +173,43 @@ class World(object):
|
|||
self.camera_manager.render(display)
|
||||
self.hud.render(display)
|
||||
|
||||
def destroy_sensors(self):
|
||||
self.camera_manager.sensor.destroy()
|
||||
self.camera_manager.sensor = None
|
||||
self.camera_manager.index = None
|
||||
|
||||
def destroy(self):
|
||||
actors = [
|
||||
self.camera_manager.sensor,
|
||||
self.collision_sensor.sensor,
|
||||
self.lane_invasion_sensor.sensor,
|
||||
self.vehicle]
|
||||
self.gnss_sensor.sensor,
|
||||
self.player]
|
||||
for actor in actors:
|
||||
if actor is not None:
|
||||
actor.destroy()
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
# -- KeyboardControl -----------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
class KeyboardControl(object):
|
||||
def __init__(self, world, start_in_autopilot):
|
||||
self._autopilot_enabled = start_in_autopilot
|
||||
self._control = carla.VehicleControl()
|
||||
if isinstance(world.player, carla.Vehicle):
|
||||
self._control = carla.VehicleControl()
|
||||
world.player.set_autopilot(self._autopilot_enabled)
|
||||
elif isinstance(world.player, carla.Walker):
|
||||
self._control = carla.WalkerControl()
|
||||
self._autopilot_enabled = False
|
||||
self._rotation = world.player.get_transform().rotation
|
||||
else:
|
||||
raise NotImplementedError("Actor type not supported")
|
||||
self._steer_cache = 0.0
|
||||
world.vehicle.set_autopilot(self._autopilot_enabled)
|
||||
world.hud.notification("Press 'H' or '?' for help.", seconds=4.0)
|
||||
|
||||
def parse_events(self, world, clock):
|
||||
def parse_events(self, client, world, clock):
|
||||
for event in pygame.event.get():
|
||||
if event.type == pygame.QUIT:
|
||||
return True
|
||||
|
@ -219,28 +232,72 @@ class KeyboardControl(object):
|
|||
world.camera_manager.next_sensor()
|
||||
elif event.key > K_0 and event.key <= K_9:
|
||||
world.camera_manager.set_sensor(event.key - 1 - K_0)
|
||||
elif event.key == K_r:
|
||||
elif event.key == K_r and not (pygame.key.get_mods() & KMOD_CTRL):
|
||||
world.camera_manager.toggle_recording()
|
||||
elif event.key == K_q:
|
||||
self._control.gear = 1 if self._control.reverse else -1
|
||||
elif event.key == K_m:
|
||||
self._control.manual_gear_shift = not self._control.manual_gear_shift
|
||||
self._control.gear = world.vehicle.get_control().gear
|
||||
world.hud.notification(
|
||||
'%s Transmission' % ('Manual' if self._control.manual_gear_shift else 'Automatic'))
|
||||
elif self._control.manual_gear_shift and event.key == K_COMMA:
|
||||
self._control.gear = max(-1, self._control.gear - 1)
|
||||
elif self._control.manual_gear_shift and event.key == K_PERIOD:
|
||||
self._control.gear = self._control.gear + 1
|
||||
elif event.key == K_p:
|
||||
self._autopilot_enabled = not self._autopilot_enabled
|
||||
world.vehicle.set_autopilot(self._autopilot_enabled)
|
||||
world.hud.notification('Autopilot %s' % ('On' if self._autopilot_enabled else 'Off'))
|
||||
elif event.key == K_r and (pygame.key.get_mods() & KMOD_CTRL):
|
||||
if (world.recording_enabled):
|
||||
client.stop_recorder()
|
||||
world.recording_enabled = False
|
||||
world.hud.notification("Recorder is OFF")
|
||||
else:
|
||||
client.start_recorder("manual_recording.rec")
|
||||
world.recording_enabled = True
|
||||
world.hud.notification("Recorder is ON")
|
||||
elif event.key == K_p and (pygame.key.get_mods() & KMOD_CTRL):
|
||||
# stop recorder
|
||||
client.stop_recorder()
|
||||
world.recording_enabled = False
|
||||
# work around to fix camera at start of replaying
|
||||
currentIndex = world.camera_manager.index
|
||||
world.destroy_sensors()
|
||||
# disable autopilot
|
||||
self._autopilot_enabled = False
|
||||
world.player.set_autopilot(self._autopilot_enabled)
|
||||
world.hud.notification("Replaying file 'manual_recording.rec'")
|
||||
# replayer
|
||||
client.replay_file("manual_recording.rec", world.recording_start, 0, 0)
|
||||
world.camera_manager.set_sensor(currentIndex)
|
||||
elif event.key == K_MINUS and (pygame.key.get_mods() & KMOD_CTRL):
|
||||
if pygame.key.get_mods() & KMOD_SHIFT:
|
||||
world.recording_start -= 10
|
||||
else:
|
||||
world.recording_start -= 1
|
||||
world.hud.notification("Recording start time is %d" % (world.recording_start))
|
||||
elif event.key == K_EQUALS and (pygame.key.get_mods() & KMOD_CTRL):
|
||||
if pygame.key.get_mods() & KMOD_SHIFT:
|
||||
world.recording_start += 10
|
||||
else:
|
||||
world.recording_start += 1
|
||||
world.hud.notification("Recording start time is %d" % (world.recording_start))
|
||||
if isinstance(self._control, carla.VehicleControl):
|
||||
if event.key == K_q:
|
||||
self._control.gear = 1 if self._control.reverse else -1
|
||||
elif event.key == K_m:
|
||||
self._control.manual_gear_shift = not self._control.manual_gear_shift
|
||||
self._control.gear = world.player.get_control().gear
|
||||
world.hud.notification('%s Transmission' % (
|
||||
'Manual' if self._control.manual_gear_shift else 'Automatic'))
|
||||
elif self._control.manual_gear_shift and event.key == K_COMMA:
|
||||
self._control.gear = max(-1, self._control.gear - 1)
|
||||
elif self._control.manual_gear_shift and event.key == K_PERIOD:
|
||||
self._control.gear = self._control.gear + 1
|
||||
elif event.key == K_p and not (pygame.key.get_mods() & KMOD_CTRL):
|
||||
self._autopilot_enabled = not self._autopilot_enabled
|
||||
world.player.set_autopilot(self._autopilot_enabled)
|
||||
world.hud.notification(
|
||||
'Autopilot %s' % ('On' if self._autopilot_enabled else 'Off'))
|
||||
if not self._autopilot_enabled:
|
||||
self._parse_keys(pygame.key.get_pressed(), clock.get_time())
|
||||
self._control.reverse = self._control.gear < 0
|
||||
if isinstance(self._control, carla.VehicleControl):
|
||||
keys = pygame.key.get_pressed()
|
||||
if sum(keys) > 0:
|
||||
self._parse_vehicle_keys(keys, clock.get_time())
|
||||
self._control.reverse = self._control.gear < 0
|
||||
world.player.apply_control(self._control)
|
||||
elif isinstance(self._control, carla.WalkerControl):
|
||||
self._parse_walker_keys(pygame.key.get_pressed(), clock.get_time())
|
||||
world.player.apply_control(self._control)
|
||||
|
||||
def _parse_keys(self, keys, milliseconds):
|
||||
def _parse_vehicle_keys(self, keys, milliseconds):
|
||||
self._control.throttle = 1.0 if keys[K_UP] or keys[K_w] else 0.0
|
||||
steer_increment = 5e-4 * milliseconds
|
||||
if keys[K_LEFT] or keys[K_a]:
|
||||
|
@ -254,13 +311,28 @@ class KeyboardControl(object):
|
|||
self._control.brake = 1.0 if keys[K_DOWN] or keys[K_s] else 0.0
|
||||
self._control.hand_brake = keys[K_SPACE]
|
||||
|
||||
def _parse_walker_keys(self, keys, milliseconds):
|
||||
self._control.speed = 0.0
|
||||
if keys[K_DOWN] or keys[K_s]:
|
||||
self._control.speed = 0.0
|
||||
if keys[K_LEFT] or keys[K_a]:
|
||||
self._control.speed = .01
|
||||
self._rotation.yaw -= 0.08 * milliseconds
|
||||
if keys[K_RIGHT] or keys[K_d]:
|
||||
self._control.speed = .01
|
||||
self._rotation.yaw += 0.08 * milliseconds
|
||||
if keys[K_UP] or keys[K_w]:
|
||||
self._control.speed = 5.556 if pygame.key.get_mods() & KMOD_SHIFT else 2.778
|
||||
self._control.jump = keys[K_SPACE]
|
||||
self._rotation.yaw = round(self._rotation.yaw, 1)
|
||||
self._control.direction = self._rotation.get_forward_vector()
|
||||
|
||||
@staticmethod
|
||||
def _is_quit_shortcut(key):
|
||||
return (key == K_ESCAPE) or (key == K_q and pygame.key.get_mods() & KMOD_CTRL)
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
# -- HUD -----------------------------------------------------------------
|
||||
# -- HUD -----------------------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
|
@ -289,11 +361,12 @@ class HUD(object):
|
|||
self.simulation_time = timestamp.elapsed_seconds
|
||||
|
||||
def tick(self, world, clock):
|
||||
self._notifications.tick(world, clock)
|
||||
if not self._show_info:
|
||||
return
|
||||
t = world.vehicle.get_transform()
|
||||
v = world.vehicle.get_velocity()
|
||||
c = world.vehicle.get_control()
|
||||
t = world.player.get_transform()
|
||||
v = world.player.get_velocity()
|
||||
c = world.player.get_control()
|
||||
heading = 'N' if abs(t.rotation.yaw) < 89.5 else ''
|
||||
heading += 'S' if abs(t.rotation.yaw) > 90.5 else ''
|
||||
heading += 'E' if 179.5 > t.rotation.yaw > 0.5 else ''
|
||||
|
@ -304,40 +377,49 @@ class HUD(object):
|
|||
collision = [x / max_col for x in collision]
|
||||
vehicles = world.world.get_actors().filter('vehicle.*')
|
||||
self._info_text = [
|
||||
'Server: % 16d FPS' % self.server_fps,
|
||||
'Server: % 16.0f FPS' % self.server_fps,
|
||||
'Client: % 16.0f FPS' % clock.get_fps(),
|
||||
'',
|
||||
'Vehicle: % 20s' % get_actor_display_name(world.vehicle, truncate=20),
|
||||
'Vehicle: % 20s' % get_actor_display_name(world.player, truncate=20),
|
||||
'Map: % 20s' % world.map.name,
|
||||
'Simulation time: % 12s' % datetime.timedelta(seconds=int(self.simulation_time)),
|
||||
'',
|
||||
'Speed: % 15.0f km/h' % (3.6 * math.sqrt(v.x**2 + v.y**2 + v.z**2)),
|
||||
'Speed: % 15.0f km/h' % (3.6 * math.sqrt(v.x ** 2 + v.y ** 2 + v.z ** 2)),
|
||||
u'Heading:% 16.0f\N{DEGREE SIGN} % 2s' % (t.rotation.yaw, heading),
|
||||
'Location:% 20s' % ('(% 5.1f, % 5.1f)' % (t.location.x, t.location.y)),
|
||||
'GNSS:% 24s' % ('(% 2.6f, % 3.6f)' % (world.gnss_sensor.lat, world.gnss_sensor.lon)),
|
||||
'Height: % 18.0f m' % t.location.z,
|
||||
'',
|
||||
('Throttle:', c.throttle, 0.0, 1.0),
|
||||
('Steer:', c.steer, -1.0, 1.0),
|
||||
('Brake:', c.brake, 0.0, 1.0),
|
||||
('Reverse:', c.reverse),
|
||||
('Hand brake:', c.hand_brake),
|
||||
('Manual:', c.manual_gear_shift),
|
||||
'Gear: %s' % {-1: 'R', 0: 'N'}.get(c.gear, c.gear),
|
||||
'']
|
||||
if isinstance(c, carla.VehicleControl):
|
||||
self._info_text += [
|
||||
('Throttle:', c.throttle, 0.0, 1.0),
|
||||
('Steer:', c.steer, -1.0, 1.0),
|
||||
('Brake:', c.brake, 0.0, 1.0),
|
||||
('Reverse:', c.reverse),
|
||||
('Hand brake:', c.hand_brake),
|
||||
('Manual:', c.manual_gear_shift),
|
||||
'Gear: %s' % {-1: 'R', 0: 'N'}.get(c.gear, c.gear)]
|
||||
elif isinstance(c, carla.WalkerControl):
|
||||
self._info_text += [
|
||||
('Speed:', c.speed, 0.0, 5.556),
|
||||
('Jump:', c.jump)]
|
||||
self._info_text += [
|
||||
'',
|
||||
'Collision:',
|
||||
collision,
|
||||
'',
|
||||
'Number of vehicles: % 8d' % len(vehicles)
|
||||
]
|
||||
'Number of vehicles: % 8d' % len(vehicles)]
|
||||
if len(vehicles) > 1:
|
||||
self._info_text += ['Nearby vehicles:']
|
||||
distance = lambda l: math.sqrt((l.x - t.location.x)**2 + (l.y - t.location.y)**2 + (l.z - t.location.z)**2)
|
||||
vehicles = [(distance(x.get_location()), x) for x in vehicles if x.id != world.vehicle.id]
|
||||
|
||||
def distance(l): return math.sqrt(
|
||||
(l.x - t.location.x) ** 2 + (l.y - t.location.y) ** 2 + (l.z - t.location.z) ** 2)
|
||||
vehicles = [(distance(x.get_location()), x) for x in vehicles if x.id != world.player.id]
|
||||
for d, vehicle in sorted(vehicles):
|
||||
if d > 200.0:
|
||||
break
|
||||
vehicle_type = get_actor_display_name(vehicle, truncate=22)
|
||||
self._info_text.append('% 4dm %s' % (d, vehicle_type))
|
||||
self._notifications.tick(world, clock)
|
||||
|
||||
def toggle_info(self):
|
||||
self._show_info = not self._show_info
|
||||
|
@ -379,18 +461,18 @@ class HUD(object):
|
|||
rect = pygame.Rect((bar_h_offset, v_offset + 8), (f * bar_width, 6))
|
||||
pygame.draw.rect(display, (255, 255, 255), rect)
|
||||
item = item[0]
|
||||
if item: # At this point has to be a str.
|
||||
if item: # At this point has to be a str.
|
||||
surface = self._font_mono.render(item, True, (255, 255, 255))
|
||||
display.blit(surface, (8, v_offset))
|
||||
v_offset += 18
|
||||
self._notifications.render(display)
|
||||
self.help.render(display)
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
# -- FadingText ----------------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
class FadingText(object):
|
||||
def __init__(self, font, dim, pos):
|
||||
self.font = font
|
||||
|
@ -449,9 +531,9 @@ class HelpText(object):
|
|||
class CollisionSensor(object):
|
||||
def __init__(self, parent_actor, hud):
|
||||
self.sensor = None
|
||||
self._history = []
|
||||
self.history = []
|
||||
self._parent = parent_actor
|
||||
self._hud = hud
|
||||
self.hud = hud
|
||||
world = self._parent.get_world()
|
||||
bp = world.get_blueprint_library().find('sensor.other.collision')
|
||||
self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)
|
||||
|
@ -462,7 +544,7 @@ class CollisionSensor(object):
|
|||
|
||||
def get_collision_history(self):
|
||||
history = collections.defaultdict(int)
|
||||
for frame, intensity in self._history:
|
||||
for frame, intensity in self.history:
|
||||
history[frame] += intensity
|
||||
return history
|
||||
|
||||
|
@ -472,23 +554,23 @@ class CollisionSensor(object):
|
|||
if not self:
|
||||
return
|
||||
actor_type = get_actor_display_name(event.other_actor)
|
||||
self._hud.notification('Collision with %r, id = %d' % (actor_type, event.other_actor.id))
|
||||
self.hud.notification('Collision with %r' % actor_type)
|
||||
impulse = event.normal_impulse
|
||||
intensity = math.sqrt(impulse.x ** 2 + impulse.y ** 2 + impulse.z ** 2)
|
||||
self._history.append((event.frame_number, intensity))
|
||||
if len(self._history) > 4000:
|
||||
self._history.pop(0)
|
||||
|
||||
self.history.append((event.frame_number, intensity))
|
||||
if len(self.history) > 4000:
|
||||
self.history.pop(0)
|
||||
|
||||
# ==============================================================================
|
||||
# -- LaneInvasionSensor --------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
class LaneInvasionSensor(object):
|
||||
def __init__(self, parent_actor, hud):
|
||||
self.sensor = None
|
||||
self._parent = parent_actor
|
||||
self._hud = hud
|
||||
self.hud = hud
|
||||
world = self._parent.get_world()
|
||||
bp = world.get_blueprint_library().find('sensor.other.lane_detector')
|
||||
self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)
|
||||
|
@ -503,25 +585,53 @@ class LaneInvasionSensor(object):
|
|||
if not self:
|
||||
return
|
||||
text = ['%r' % str(x).split()[-1] for x in set(event.crossed_lane_markings)]
|
||||
self._hud.notification('Crossed line %s' % ' and '.join(text))
|
||||
self.hud.notification('Crossed line %s' % ' and '.join(text))
|
||||
|
||||
# ==============================================================================
|
||||
# -- GnssSensor --------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
class GnssSensor(object):
|
||||
def __init__(self, parent_actor):
|
||||
self.sensor = None
|
||||
self._parent = parent_actor
|
||||
self.lat = 0.0
|
||||
self.lon = 0.0
|
||||
world = self._parent.get_world()
|
||||
bp = world.get_blueprint_library().find('sensor.other.gnss')
|
||||
self.sensor = world.spawn_actor(bp, carla.Transform(carla.Location(x=1.0, z=2.8)),
|
||||
attach_to=self._parent)
|
||||
# We need to pass the lambda a weak reference to self to avoid circular
|
||||
# reference.
|
||||
weak_self = weakref.ref(self)
|
||||
self.sensor.listen(lambda event: GnssSensor._on_gnss_event(weak_self, event))
|
||||
|
||||
@staticmethod
|
||||
def _on_gnss_event(weak_self, event):
|
||||
self = weak_self()
|
||||
if not self:
|
||||
return
|
||||
self.lat = event.latitude
|
||||
self.lon = event.longitude
|
||||
|
||||
# ==============================================================================
|
||||
# -- CameraManager -------------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
|
||||
class CameraManager(object):
|
||||
def __init__(self, parent_actor, hud):
|
||||
self.sensor = None
|
||||
self._surface = None
|
||||
self.surface = None
|
||||
self._parent = parent_actor
|
||||
self._hud = hud
|
||||
self._recording = False
|
||||
self.hud = hud
|
||||
self.recording = False
|
||||
self._camera_transforms = [
|
||||
carla.Transform(carla.Location(x=-5.5, z=2.8), carla.Rotation(pitch=-15)),
|
||||
carla.Transform(carla.Location(x=1.6, z=1.7))]
|
||||
self._transform_index = 1
|
||||
self._sensors = [
|
||||
self.transform_index = 1
|
||||
self.sensors = [
|
||||
['sensor.camera.rgb', cc.Raw, 'Camera RGB'],
|
||||
['sensor.camera.depth', cc.Raw, 'Camera Depth (Raw)'],
|
||||
['sensor.camera.depth', cc.Depth, 'Camera Depth (Gray Scale)'],
|
||||
|
@ -532,75 +642,77 @@ class CameraManager(object):
|
|||
['sensor.lidar.ray_cast', None, 'Lidar (Ray-Cast)']]
|
||||
world = self._parent.get_world()
|
||||
bp_library = world.get_blueprint_library()
|
||||
for item in self._sensors:
|
||||
for item in self.sensors:
|
||||
bp = bp_library.find(item[0])
|
||||
if item[0].startswith('sensor.camera'):
|
||||
bp.set_attribute('image_size_x', str(hud.dim[0]))
|
||||
bp.set_attribute('image_size_y', str(hud.dim[1]))
|
||||
elif item[0].startswith('sensor.lidar'):
|
||||
bp.set_attribute('range', '5000')
|
||||
item.append(bp)
|
||||
self._index = None
|
||||
self.index = None
|
||||
|
||||
def toggle_camera(self):
|
||||
self._transform_index = (self._transform_index + 1) % len(self._camera_transforms)
|
||||
self.sensor.set_transform(self._camera_transforms[self._transform_index])
|
||||
self.transform_index = (self.transform_index + 1) % len(self._camera_transforms)
|
||||
self.sensor.set_transform(self._camera_transforms[self.transform_index])
|
||||
|
||||
def set_sensor(self, index, notify=True):
|
||||
index = index % len(self._sensors)
|
||||
needs_respawn = True if self._index is None \
|
||||
else self._sensors[index][0] != self._sensors[self._index][0]
|
||||
index = index % len(self.sensors)
|
||||
needs_respawn = True if self.index is None \
|
||||
else self.sensors[index][0] != self.sensors[self.index][0]
|
||||
if needs_respawn:
|
||||
if self.sensor is not None:
|
||||
self.sensor.destroy()
|
||||
self._surface = None
|
||||
self.surface = None
|
||||
self.sensor = self._parent.get_world().spawn_actor(
|
||||
self._sensors[index][-1],
|
||||
self._camera_transforms[self._transform_index],
|
||||
self.sensors[index][-1],
|
||||
self._camera_transforms[self.transform_index],
|
||||
attach_to=self._parent)
|
||||
# We need to pass the lambda a weak reference to self to avoid
|
||||
# circular reference.
|
||||
weak_self = weakref.ref(self)
|
||||
self.sensor.listen(lambda image: CameraManager._parse_image(weak_self, image))
|
||||
if notify:
|
||||
self._hud.notification(self._sensors[index][2])
|
||||
self._index = index
|
||||
self.hud.notification(self.sensors[index][2])
|
||||
self.index = index
|
||||
|
||||
def next_sensor(self):
|
||||
self.set_sensor(self._index + 1)
|
||||
self.set_sensor(self.index + 1)
|
||||
|
||||
def toggle_recording(self):
|
||||
self._recording = not self._recording
|
||||
self._hud.notification('Recording %s' % ('On' if self._recording else 'Off'))
|
||||
self.recording = not self.recording
|
||||
self.hud.notification('Recording %s' % ('On' if self.recording else 'Off'))
|
||||
|
||||
def render(self, display):
|
||||
if self._surface is not None:
|
||||
display.blit(self._surface, (0, 0))
|
||||
if self.surface is not None:
|
||||
display.blit(self.surface, (0, 0))
|
||||
|
||||
@staticmethod
|
||||
def _parse_image(weak_self, image):
|
||||
self = weak_self()
|
||||
if not self:
|
||||
return
|
||||
if self._sensors[self._index][0].startswith('sensor.lidar'):
|
||||
if self.sensors[self.index][0].startswith('sensor.lidar'):
|
||||
points = np.frombuffer(image.raw_data, dtype=np.dtype('f4'))
|
||||
points = np.reshape(points, (int(points.shape[0] / 3), 3))
|
||||
lidar_data = np.array(points[:, :2])
|
||||
lidar_data *= min(self._hud.dim) / 100.0
|
||||
lidar_data += (0.5 * self._hud.dim[0], 0.5 * self._hud.dim[1])
|
||||
lidar_data = np.fabs(lidar_data)
|
||||
lidar_data *= min(self.hud.dim) / 100.0
|
||||
lidar_data += (0.5 * self.hud.dim[0], 0.5 * self.hud.dim[1])
|
||||
lidar_data = np.fabs(lidar_data) # pylint: disable=E1111
|
||||
lidar_data = lidar_data.astype(np.int32)
|
||||
lidar_data = np.reshape(lidar_data, (-1, 2))
|
||||
lidar_img_size = (self._hud.dim[0], self._hud.dim[1], 3)
|
||||
lidar_img_size = (self.hud.dim[0], self.hud.dim[1], 3)
|
||||
lidar_img = np.zeros(lidar_img_size)
|
||||
lidar_img[tuple(lidar_data.T)] = (255, 255, 255)
|
||||
self._surface = pygame.surfarray.make_surface(lidar_img)
|
||||
self.surface = pygame.surfarray.make_surface(lidar_img)
|
||||
else:
|
||||
image.convert(self._sensors[self._index][1])
|
||||
image.convert(self.sensors[self.index][1])
|
||||
array = np.frombuffer(image.raw_data, dtype=np.dtype("uint8"))
|
||||
array = np.reshape(array, (image.height, image.width, 4))
|
||||
array = array[:, :, :3]
|
||||
array = array[:, :, ::-1]
|
||||
self._surface = pygame.surfarray.make_surface(array.swapaxes(0, 1))
|
||||
if self._recording:
|
||||
self.surface = pygame.surfarray.make_surface(array.swapaxes(0, 1))
|
||||
if self.recording:
|
||||
image.save_to_disk('_out/%08d' % image.frame_number)
|
||||
|
||||
|
||||
|
@ -622,13 +734,13 @@ def game_loop(args):
|
|||
pygame.HWSURFACE | pygame.DOUBLEBUF)
|
||||
|
||||
hud = HUD(args.width, args.height)
|
||||
world = World(client.get_world(), hud)
|
||||
world = World(client.get_world(), hud, args.filter)
|
||||
controller = KeyboardControl(world, False)
|
||||
|
||||
if args.agent == "Roaming":
|
||||
agent = RoamingAgent(world.vehicle)
|
||||
agent = RoamingAgent(world.player)
|
||||
else:
|
||||
agent = BasicAgent(world.vehicle)
|
||||
agent = BasicAgent(world.player)
|
||||
spawn_point = world.map.get_spawn_points()[0]
|
||||
agent.set_destination((spawn_point.location.x,
|
||||
spawn_point.location.y,
|
||||
|
@ -636,7 +748,7 @@ def game_loop(args):
|
|||
|
||||
clock = pygame.time.Clock()
|
||||
while True:
|
||||
if controller.parse_events(world, clock):
|
||||
if controller.parse_events(client, world, clock):
|
||||
return
|
||||
|
||||
# as soon as the server is ready continue!
|
||||
|
@ -647,7 +759,8 @@ def game_loop(args):
|
|||
world.render(display)
|
||||
pygame.display.flip()
|
||||
control = agent.run_step()
|
||||
world.vehicle.apply_control(control)
|
||||
control.manual_gear_shift = False
|
||||
world.player.apply_control(control)
|
||||
|
||||
finally:
|
||||
if world is not None:
|
||||
|
@ -685,7 +798,11 @@ def main():
|
|||
metavar='WIDTHxHEIGHT',
|
||||
default='1280x720',
|
||||
help='window resolution (default: 1280x720)')
|
||||
|
||||
argparser.add_argument(
|
||||
'--filter',
|
||||
metavar='PATTERN',
|
||||
default='vehicle.*',
|
||||
help='actor filter (default: "vehicle.*")')
|
||||
argparser.add_argument("-a", "--agent", type=str,
|
||||
choices=["Roaming", "Basic"],
|
||||
help="select which agent to run",
|
||||
|
@ -707,10 +824,7 @@ def main():
|
|||
|
||||
except KeyboardInterrupt:
|
||||
print('\nCancelled by user. Bye!')
|
||||
except Exception as error:
|
||||
logging.exception(error)
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
||||
main()
|
||||
|
|
|
@ -134,7 +134,7 @@ def find_weather_presets():
|
|||
|
||||
def get_actor_display_name(actor, truncate=250):
|
||||
name = ' '.join(actor.type_id.replace('_', '.').title().split('.')[1:])
|
||||
return (name[:truncate-1] + u'\u2026') if len(name) > truncate else name
|
||||
return (name[:truncate - 1] + u'\u2026') if len(name) > truncate else name
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
|
@ -162,8 +162,8 @@ class World(object):
|
|||
|
||||
def restart(self):
|
||||
# Keep same camera config if the camera manager exists.
|
||||
cam_index = self.camera_manager._index if self.camera_manager is not None else 0
|
||||
cam_pos_index = self.camera_manager._transform_index if self.camera_manager is not None else 0
|
||||
cam_index = self.camera_manager.index if self.camera_manager is not None else 0
|
||||
cam_pos_index = self.camera_manager.transform_index if self.camera_manager is not None else 0
|
||||
# Get a random blueprint.
|
||||
blueprint = random.choice(self.world.get_blueprint_library().filter(self._actor_filter))
|
||||
blueprint.set_attribute('role_name', 'hero')
|
||||
|
@ -187,7 +187,7 @@ class World(object):
|
|||
self.lane_invasion_sensor = LaneInvasionSensor(self.player, self.hud)
|
||||
self.gnss_sensor = GnssSensor(self.player)
|
||||
self.camera_manager = CameraManager(self.player, self.hud)
|
||||
self.camera_manager._transform_index = cam_pos_index
|
||||
self.camera_manager.transform_index = cam_pos_index
|
||||
self.camera_manager.set_sensor(cam_index, notify=False)
|
||||
actor_type = get_actor_display_name(self.player)
|
||||
self.hud.notification(actor_type)
|
||||
|
@ -206,10 +206,10 @@ class World(object):
|
|||
self.camera_manager.render(display)
|
||||
self.hud.render(display)
|
||||
|
||||
def destroySensors(self):
|
||||
self.camera_manager.sensor.destroy()
|
||||
self.camera_manager.sensor = None
|
||||
self.camera_manager._index = None
|
||||
def destroy_sensors(self):
|
||||
self.camera_manager.sensor.destroy()
|
||||
self.camera_manager.sensor = None
|
||||
self.camera_manager.index = None
|
||||
|
||||
def destroy(self):
|
||||
actors = [
|
||||
|
@ -281,8 +281,8 @@ class KeyboardControl(object):
|
|||
client.stop_recorder()
|
||||
world.recording_enabled = False
|
||||
# work around to fix camera at start of replaying
|
||||
currentIndex = world.camera_manager._index
|
||||
world.destroySensors()
|
||||
currentIndex = world.camera_manager.index
|
||||
world.destroy_sensors()
|
||||
# disable autopilot
|
||||
self._autopilot_enabled = False
|
||||
world.player.set_autopilot(self._autopilot_enabled)
|
||||
|
@ -308,7 +308,8 @@ class KeyboardControl(object):
|
|||
elif event.key == K_m:
|
||||
self._control.manual_gear_shift = not self._control.manual_gear_shift
|
||||
self._control.gear = world.player.get_control().gear
|
||||
world.hud.notification('%s Transmission' % ('Manual' if self._control.manual_gear_shift else 'Automatic'))
|
||||
world.hud.notification('%s Transmission' %
|
||||
('Manual' if self._control.manual_gear_shift else 'Automatic'))
|
||||
elif self._control.manual_gear_shift and event.key == K_COMMA:
|
||||
self._control.gear = max(-1, self._control.gear - 1)
|
||||
elif self._control.manual_gear_shift and event.key == K_PERIOD:
|
||||
|
@ -488,7 +489,7 @@ class HUD(object):
|
|||
rect = pygame.Rect((bar_h_offset, v_offset + 8), (f * bar_width, 6))
|
||||
pygame.draw.rect(display, (255, 255, 255), rect)
|
||||
item = item[0]
|
||||
if item: # At this point has to be a str.
|
||||
if item: # At this point has to be a str.
|
||||
surface = self._font_mono.render(item, True, (255, 255, 255))
|
||||
display.blit(surface, (8, v_offset))
|
||||
v_offset += 18
|
||||
|
@ -561,9 +562,9 @@ class HelpText(object):
|
|||
class CollisionSensor(object):
|
||||
def __init__(self, parent_actor, hud):
|
||||
self.sensor = None
|
||||
self._history = []
|
||||
self.history = []
|
||||
self._parent = parent_actor
|
||||
self._hud = hud
|
||||
self.hud = hud
|
||||
world = self._parent.get_world()
|
||||
bp = world.get_blueprint_library().find('sensor.other.collision')
|
||||
self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)
|
||||
|
@ -574,7 +575,7 @@ class CollisionSensor(object):
|
|||
|
||||
def get_collision_history(self):
|
||||
history = collections.defaultdict(int)
|
||||
for frame, intensity in self._history:
|
||||
for frame, intensity in self.history:
|
||||
history[frame] += intensity
|
||||
return history
|
||||
|
||||
|
@ -584,12 +585,12 @@ class CollisionSensor(object):
|
|||
if not self:
|
||||
return
|
||||
actor_type = get_actor_display_name(event.other_actor)
|
||||
self._hud.notification('Collision with %r' % actor_type)
|
||||
self.hud.notification('Collision with %r' % actor_type)
|
||||
impulse = event.normal_impulse
|
||||
intensity = math.sqrt(impulse.x**2 + impulse.y**2 + impulse.z**2)
|
||||
self._history.append((event.frame_number, intensity))
|
||||
if len(self._history) > 4000:
|
||||
self._history.pop(0)
|
||||
self.history.append((event.frame_number, intensity))
|
||||
if len(self.history) > 4000:
|
||||
self.history.pop(0)
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
|
@ -601,7 +602,7 @@ class LaneInvasionSensor(object):
|
|||
def __init__(self, parent_actor, hud):
|
||||
self.sensor = None
|
||||
self._parent = parent_actor
|
||||
self._hud = hud
|
||||
self.hud = hud
|
||||
world = self._parent.get_world()
|
||||
bp = world.get_blueprint_library().find('sensor.other.lane_detector')
|
||||
self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)
|
||||
|
@ -616,7 +617,7 @@ class LaneInvasionSensor(object):
|
|||
if not self:
|
||||
return
|
||||
text = ['%r' % str(x).split()[-1] for x in set(event.crossed_lane_markings)]
|
||||
self._hud.notification('Crossed line %s' % ' and '.join(text))
|
||||
self.hud.notification('Crossed line %s' % ' and '.join(text))
|
||||
|
||||
# ==============================================================================
|
||||
# -- GnssSensor --------------------------------------------------------
|
||||
|
@ -654,25 +655,26 @@ class GnssSensor(object):
|
|||
class CameraManager(object):
|
||||
def __init__(self, parent_actor, hud):
|
||||
self.sensor = None
|
||||
self._surface = None
|
||||
self.surface = None
|
||||
self._parent = parent_actor
|
||||
self._hud = hud
|
||||
self._recording = False
|
||||
self.hud = hud
|
||||
self.recording = False
|
||||
self._camera_transforms = [
|
||||
carla.Transform(carla.Location(x=-5.5, z=2.8), carla.Rotation(pitch=-15)),
|
||||
carla.Transform(carla.Location(x=1.6, z=1.7))]
|
||||
self._transform_index = 1
|
||||
self._sensors = [
|
||||
self.transform_index = 1
|
||||
self.sensors = [
|
||||
['sensor.camera.rgb', cc.Raw, 'Camera RGB'],
|
||||
['sensor.camera.depth', cc.Raw, 'Camera Depth (Raw)'],
|
||||
['sensor.camera.depth', cc.Depth, 'Camera Depth (Gray Scale)'],
|
||||
['sensor.camera.depth', cc.LogarithmicDepth, 'Camera Depth (Logarithmic Gray Scale)'],
|
||||
['sensor.camera.semantic_segmentation', cc.Raw, 'Camera Semantic Segmentation (Raw)'],
|
||||
['sensor.camera.semantic_segmentation', cc.CityScapesPalette, 'Camera Semantic Segmentation (CityScapes Palette)'],
|
||||
['sensor.camera.semantic_segmentation', cc.CityScapesPalette,
|
||||
'Camera Semantic Segmentation (CityScapes Palette)'],
|
||||
['sensor.lidar.ray_cast', None, 'Lidar (Ray-Cast)']]
|
||||
world = self._parent.get_world()
|
||||
bp_library = world.get_blueprint_library()
|
||||
for item in self._sensors:
|
||||
for item in self.sensors:
|
||||
bp = bp_library.find(item[0])
|
||||
if item[0].startswith('sensor.camera'):
|
||||
bp.set_attribute('image_size_x', str(hud.dim[0]))
|
||||
|
@ -680,69 +682,69 @@ class CameraManager(object):
|
|||
elif item[0].startswith('sensor.lidar'):
|
||||
bp.set_attribute('range', '5000')
|
||||
item.append(bp)
|
||||
self._index = None
|
||||
self.index = None
|
||||
|
||||
def toggle_camera(self):
|
||||
self._transform_index = (self._transform_index + 1) % len(self._camera_transforms)
|
||||
self.sensor.set_transform(self._camera_transforms[self._transform_index])
|
||||
self.transform_index = (self.transform_index + 1) % len(self._camera_transforms)
|
||||
self.sensor.set_transform(self._camera_transforms[self.transform_index])
|
||||
|
||||
def set_sensor(self, index, notify=True):
|
||||
index = index % len(self._sensors)
|
||||
needs_respawn = True if self._index is None \
|
||||
else self._sensors[index][0] != self._sensors[self._index][0]
|
||||
index = index % len(self.sensors)
|
||||
needs_respawn = True if self.index is None \
|
||||
else self.sensors[index][0] != self.sensors[self.index][0]
|
||||
if needs_respawn:
|
||||
if self.sensor is not None:
|
||||
self.sensor.destroy()
|
||||
self._surface = None
|
||||
self.surface = None
|
||||
self.sensor = self._parent.get_world().spawn_actor(
|
||||
self._sensors[index][-1],
|
||||
self._camera_transforms[self._transform_index],
|
||||
self.sensors[index][-1],
|
||||
self._camera_transforms[self.transform_index],
|
||||
attach_to=self._parent)
|
||||
# We need to pass the lambda a weak reference to self to avoid
|
||||
# circular reference.
|
||||
weak_self = weakref.ref(self)
|
||||
self.sensor.listen(lambda image: CameraManager._parse_image(weak_self, image))
|
||||
if notify:
|
||||
self._hud.notification(self._sensors[index][2])
|
||||
self._index = index
|
||||
self.hud.notification(self.sensors[index][2])
|
||||
self.index = index
|
||||
|
||||
def next_sensor(self):
|
||||
self.set_sensor(self._index + 1)
|
||||
self.set_sensor(self.index + 1)
|
||||
|
||||
def toggle_recording(self):
|
||||
self._recording = not self._recording
|
||||
self._hud.notification('Recording %s' % ('On' if self._recording else 'Off'))
|
||||
self.recording = not self.recording
|
||||
self.hud.notification('Recording %s' % ('On' if self.recording else 'Off'))
|
||||
|
||||
def render(self, display):
|
||||
if self._surface is not None:
|
||||
display.blit(self._surface, (0, 0))
|
||||
if self.surface is not None:
|
||||
display.blit(self.surface, (0, 0))
|
||||
|
||||
@staticmethod
|
||||
def _parse_image(weak_self, image):
|
||||
self = weak_self()
|
||||
if not self:
|
||||
return
|
||||
if self._sensors[self._index][0].startswith('sensor.lidar'):
|
||||
if self.sensors[self.index][0].startswith('sensor.lidar'):
|
||||
points = np.frombuffer(image.raw_data, dtype=np.dtype('f4'))
|
||||
points = np.reshape(points, (int(points.shape[0]/3), 3))
|
||||
points = np.reshape(points, (int(points.shape[0] / 3), 3))
|
||||
lidar_data = np.array(points[:, :2])
|
||||
lidar_data *= min(self._hud.dim) / 100.0
|
||||
lidar_data += (0.5 * self._hud.dim[0], 0.5 * self._hud.dim[1])
|
||||
lidar_data = np.fabs(lidar_data)
|
||||
lidar_data *= min(self.hud.dim) / 100.0
|
||||
lidar_data += (0.5 * self.hud.dim[0], 0.5 * self.hud.dim[1])
|
||||
lidar_data = np.fabs(lidar_data) # pylint: disable=E1111
|
||||
lidar_data = lidar_data.astype(np.int32)
|
||||
lidar_data = np.reshape(lidar_data, (-1, 2))
|
||||
lidar_img_size = (self._hud.dim[0], self._hud.dim[1], 3)
|
||||
lidar_img_size = (self.hud.dim[0], self.hud.dim[1], 3)
|
||||
lidar_img = np.zeros(lidar_img_size)
|
||||
lidar_img[tuple(lidar_data.T)] = (255, 255, 255)
|
||||
self._surface = pygame.surfarray.make_surface(lidar_img)
|
||||
self.surface = pygame.surfarray.make_surface(lidar_img)
|
||||
else:
|
||||
image.convert(self._sensors[self._index][1])
|
||||
image.convert(self.sensors[self.index][1])
|
||||
array = np.frombuffer(image.raw_data, dtype=np.dtype("uint8"))
|
||||
array = np.reshape(array, (image.height, image.width, 4))
|
||||
array = array[:, :, :3]
|
||||
array = array[:, :, ::-1]
|
||||
self._surface = pygame.surfarray.make_surface(array.swapaxes(0, 1))
|
||||
if self._recording:
|
||||
self.surface = pygame.surfarray.make_surface(array.swapaxes(0, 1))
|
||||
if self.recording:
|
||||
image.save_to_disk('_out/%08d' % image.frame_number)
|
||||
|
||||
|
||||
|
|
|
@ -50,7 +50,6 @@ from carla import ColorConverter as cc
|
|||
|
||||
import argparse
|
||||
import collections
|
||||
from configparser import ConfigParser
|
||||
import datetime
|
||||
import logging
|
||||
import math
|
||||
|
@ -58,6 +57,14 @@ import random
|
|||
import re
|
||||
import weakref
|
||||
|
||||
if sys.version_info >= (3, 0):
|
||||
|
||||
from configparser import ConfigParser
|
||||
|
||||
else:
|
||||
|
||||
from ConfigParser import RawConfigParser as ConfigParser
|
||||
|
||||
try:
|
||||
import pygame
|
||||
from pygame.locals import KMOD_CTRL
|
||||
|
@ -110,7 +117,7 @@ def find_weather_presets():
|
|||
|
||||
def get_actor_display_name(actor, truncate=250):
|
||||
name = ' '.join(actor.type_id.replace('_', '.').title().split('.')[1:])
|
||||
return (name[:truncate-1] + u'\u2026') if len(name) > truncate else name
|
||||
return (name[:truncate - 1] + u'\u2026') if len(name) > truncate else name
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
|
@ -135,8 +142,8 @@ class World(object):
|
|||
|
||||
def restart(self):
|
||||
# Keep same camera config if the camera manager exists.
|
||||
cam_index = self.camera_manager._index if self.camera_manager is not None else 0
|
||||
cam_pos_index = self.camera_manager._transform_index if self.camera_manager is not None else 0
|
||||
cam_index = self.camera_manager.index if self.camera_manager is not None else 0
|
||||
cam_pos_index = self.camera_manager.transform_index if self.camera_manager is not None else 0
|
||||
# Get a random blueprint.
|
||||
blueprint = random.choice(self.world.get_blueprint_library().filter(self._actor_filter))
|
||||
blueprint.set_attribute('role_name', 'hero')
|
||||
|
@ -160,7 +167,7 @@ class World(object):
|
|||
self.lane_invasion_sensor = LaneInvasionSensor(self.player, self.hud)
|
||||
self.gnss_sensor = GnssSensor(self.player)
|
||||
self.camera_manager = CameraManager(self.player, self.hud)
|
||||
self.camera_manager._transform_index = cam_pos_index
|
||||
self.camera_manager.transform_index = cam_pos_index
|
||||
self.camera_manager.set_sensor(cam_index, notify=False)
|
||||
actor_type = get_actor_display_name(self.player)
|
||||
self.hud.notification(actor_type)
|
||||
|
@ -277,7 +284,8 @@ class DualControl(object):
|
|||
elif event.key == K_m:
|
||||
self._control.manual_gear_shift = not self._control.manual_gear_shift
|
||||
self._control.gear = world.player.get_control().gear
|
||||
world.hud.notification('%s Transmission' % ('Manual' if self._control.manual_gear_shift else 'Automatic'))
|
||||
world.hud.notification('%s Transmission' %
|
||||
('Manual' if self._control.manual_gear_shift else 'Automatic'))
|
||||
elif self._control.manual_gear_shift and event.key == K_COMMA:
|
||||
self._control.gear = max(-1, self._control.gear - 1)
|
||||
elif self._control.manual_gear_shift and event.key == K_PERIOD:
|
||||
|
@ -343,10 +351,8 @@ class DualControl(object):
|
|||
|
||||
#toggle = jsButtons[self._reverse_idx]
|
||||
|
||||
|
||||
self._control.hand_brake = bool(jsButtons[self._handbrake_idx])
|
||||
|
||||
|
||||
def _parse_walker_keys(self, keys, milliseconds):
|
||||
self._control.speed = 0.0
|
||||
if keys[K_DOWN] or keys[K_s]:
|
||||
|
@ -496,7 +502,7 @@ class HUD(object):
|
|||
rect = pygame.Rect((bar_h_offset, v_offset + 8), (f * bar_width, 6))
|
||||
pygame.draw.rect(display, (255, 255, 255), rect)
|
||||
item = item[0]
|
||||
if item: # At this point has to be a str.
|
||||
if item: # At this point has to be a str.
|
||||
surface = self._font_mono.render(item, True, (255, 255, 255))
|
||||
display.blit(surface, (8, v_offset))
|
||||
v_offset += 18
|
||||
|
@ -569,9 +575,9 @@ class HelpText(object):
|
|||
class CollisionSensor(object):
|
||||
def __init__(self, parent_actor, hud):
|
||||
self.sensor = None
|
||||
self._history = []
|
||||
self.history = []
|
||||
self._parent = parent_actor
|
||||
self._hud = hud
|
||||
self.hud = hud
|
||||
world = self._parent.get_world()
|
||||
bp = world.get_blueprint_library().find('sensor.other.collision')
|
||||
self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)
|
||||
|
@ -582,7 +588,7 @@ class CollisionSensor(object):
|
|||
|
||||
def get_collision_history(self):
|
||||
history = collections.defaultdict(int)
|
||||
for frame, intensity in self._history:
|
||||
for frame, intensity in self.history:
|
||||
history[frame] += intensity
|
||||
return history
|
||||
|
||||
|
@ -592,12 +598,12 @@ class CollisionSensor(object):
|
|||
if not self:
|
||||
return
|
||||
actor_type = get_actor_display_name(event.other_actor)
|
||||
self._hud.notification('Collision with %r' % actor_type)
|
||||
self.hud.notification('Collision with %r' % actor_type)
|
||||
impulse = event.normal_impulse
|
||||
intensity = math.sqrt(impulse.x**2 + impulse.y**2 + impulse.z**2)
|
||||
self._history.append((event.frame_number, intensity))
|
||||
if len(self._history) > 4000:
|
||||
self._history.pop(0)
|
||||
self.history.append((event.frame_number, intensity))
|
||||
if len(self.history) > 4000:
|
||||
self.history.pop(0)
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
|
@ -609,7 +615,7 @@ class LaneInvasionSensor(object):
|
|||
def __init__(self, parent_actor, hud):
|
||||
self.sensor = None
|
||||
self._parent = parent_actor
|
||||
self._hud = hud
|
||||
self.hud = hud
|
||||
world = self._parent.get_world()
|
||||
bp = world.get_blueprint_library().find('sensor.other.lane_detector')
|
||||
self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)
|
||||
|
@ -624,7 +630,7 @@ class LaneInvasionSensor(object):
|
|||
if not self:
|
||||
return
|
||||
text = ['%r' % str(x).split()[-1] for x in set(event.crossed_lane_markings)]
|
||||
self._hud.notification('Crossed line %s' % ' and '.join(text))
|
||||
self.hud.notification('Crossed line %s' % ' and '.join(text))
|
||||
|
||||
# ==============================================================================
|
||||
# -- GnssSensor --------------------------------------------------------
|
||||
|
@ -662,25 +668,26 @@ class GnssSensor(object):
|
|||
class CameraManager(object):
|
||||
def __init__(self, parent_actor, hud):
|
||||
self.sensor = None
|
||||
self._surface = None
|
||||
self.surface = None
|
||||
self._parent = parent_actor
|
||||
self._hud = hud
|
||||
self._recording = False
|
||||
self.hud = hud
|
||||
self.recording = False
|
||||
self._camera_transforms = [
|
||||
carla.Transform(carla.Location(x=-5.5, z=2.8), carla.Rotation(pitch=-15)),
|
||||
carla.Transform(carla.Location(x=1.6, z=1.7))]
|
||||
self._transform_index = 1
|
||||
self._sensors = [
|
||||
self.transform_index = 1
|
||||
self.sensors = [
|
||||
['sensor.camera.rgb', cc.Raw, 'Camera RGB'],
|
||||
['sensor.camera.depth', cc.Raw, 'Camera Depth (Raw)'],
|
||||
['sensor.camera.depth', cc.Depth, 'Camera Depth (Gray Scale)'],
|
||||
['sensor.camera.depth', cc.LogarithmicDepth, 'Camera Depth (Logarithmic Gray Scale)'],
|
||||
['sensor.camera.semantic_segmentation', cc.Raw, 'Camera Semantic Segmentation (Raw)'],
|
||||
['sensor.camera.semantic_segmentation', cc.CityScapesPalette, 'Camera Semantic Segmentation (CityScapes Palette)'],
|
||||
['sensor.camera.semantic_segmentation', cc.CityScapesPalette,
|
||||
'Camera Semantic Segmentation (CityScapes Palette)'],
|
||||
['sensor.lidar.ray_cast', None, 'Lidar (Ray-Cast)']]
|
||||
world = self._parent.get_world()
|
||||
bp_library = world.get_blueprint_library()
|
||||
for item in self._sensors:
|
||||
for item in self.sensors:
|
||||
bp = bp_library.find(item[0])
|
||||
if item[0].startswith('sensor.camera'):
|
||||
bp.set_attribute('image_size_x', str(hud.dim[0]))
|
||||
|
@ -688,69 +695,69 @@ class CameraManager(object):
|
|||
elif item[0].startswith('sensor.lidar'):
|
||||
bp.set_attribute('range', '5000')
|
||||
item.append(bp)
|
||||
self._index = None
|
||||
self.index = None
|
||||
|
||||
def toggle_camera(self):
|
||||
self._transform_index = (self._transform_index + 1) % len(self._camera_transforms)
|
||||
self.sensor.set_transform(self._camera_transforms[self._transform_index])
|
||||
self.transform_index = (self.transform_index + 1) % len(self._camera_transforms)
|
||||
self.sensor.set_transform(self._camera_transforms[self.transform_index])
|
||||
|
||||
def set_sensor(self, index, notify=True):
|
||||
index = index % len(self._sensors)
|
||||
needs_respawn = True if self._index is None \
|
||||
else self._sensors[index][0] != self._sensors[self._index][0]
|
||||
index = index % len(self.sensors)
|
||||
needs_respawn = True if self.index is None \
|
||||
else self.sensors[index][0] != self.sensors[self.index][0]
|
||||
if needs_respawn:
|
||||
if self.sensor is not None:
|
||||
self.sensor.destroy()
|
||||
self._surface = None
|
||||
self.surface = None
|
||||
self.sensor = self._parent.get_world().spawn_actor(
|
||||
self._sensors[index][-1],
|
||||
self._camera_transforms[self._transform_index],
|
||||
self.sensors[index][-1],
|
||||
self._camera_transforms[self.transform_index],
|
||||
attach_to=self._parent)
|
||||
# We need to pass the lambda a weak reference to self to avoid
|
||||
# circular reference.
|
||||
weak_self = weakref.ref(self)
|
||||
self.sensor.listen(lambda image: CameraManager._parse_image(weak_self, image))
|
||||
if notify:
|
||||
self._hud.notification(self._sensors[index][2])
|
||||
self._index = index
|
||||
self.hud.notification(self.sensors[index][2])
|
||||
self.index = index
|
||||
|
||||
def next_sensor(self):
|
||||
self.set_sensor(self._index + 1)
|
||||
self.set_sensor(self.index + 1)
|
||||
|
||||
def toggle_recording(self):
|
||||
self._recording = not self._recording
|
||||
self._hud.notification('Recording %s' % ('On' if self._recording else 'Off'))
|
||||
self.recording = not self.recording
|
||||
self.hud.notification('Recording %s' % ('On' if self.recording else 'Off'))
|
||||
|
||||
def render(self, display):
|
||||
if self._surface is not None:
|
||||
display.blit(self._surface, (0, 0))
|
||||
if self.surface is not None:
|
||||
display.blit(self.surface, (0, 0))
|
||||
|
||||
@staticmethod
|
||||
def _parse_image(weak_self, image):
|
||||
self = weak_self()
|
||||
if not self:
|
||||
return
|
||||
if self._sensors[self._index][0].startswith('sensor.lidar'):
|
||||
if self.sensors[self.index][0].startswith('sensor.lidar'):
|
||||
points = np.frombuffer(image.raw_data, dtype=np.dtype('f4'))
|
||||
points = np.reshape(points, (int(points.shape[0]/3), 3))
|
||||
points = np.reshape(points, (int(points.shape[0] / 3), 3))
|
||||
lidar_data = np.array(points[:, :2])
|
||||
lidar_data *= min(self._hud.dim) / 100.0
|
||||
lidar_data += (0.5 * self._hud.dim[0], 0.5 * self._hud.dim[1])
|
||||
lidar_data = np.fabs(lidar_data)
|
||||
lidar_data *= min(self.hud.dim) / 100.0
|
||||
lidar_data += (0.5 * self.hud.dim[0], 0.5 * self.hud.dim[1])
|
||||
lidar_data = np.fabs(lidar_data) # pylint: disable=E1111
|
||||
lidar_data = lidar_data.astype(np.int32)
|
||||
lidar_data = np.reshape(lidar_data, (-1, 2))
|
||||
lidar_img_size = (self._hud.dim[0], self._hud.dim[1], 3)
|
||||
lidar_img_size = (self.hud.dim[0], self.hud.dim[1], 3)
|
||||
lidar_img = np.zeros(lidar_img_size)
|
||||
lidar_img[tuple(lidar_data.T)] = (255, 255, 255)
|
||||
self._surface = pygame.surfarray.make_surface(lidar_img)
|
||||
self.surface = pygame.surfarray.make_surface(lidar_img)
|
||||
else:
|
||||
image.convert(self._sensors[self._index][1])
|
||||
image.convert(self.sensors[self.index][1])
|
||||
array = np.frombuffer(image.raw_data, dtype=np.dtype("uint8"))
|
||||
array = np.reshape(array, (image.height, image.width, 4))
|
||||
array = array[:, :, :3]
|
||||
array = array[:, :, ::-1]
|
||||
self._surface = pygame.surfarray.make_surface(array.swapaxes(0, 1))
|
||||
if self._recording:
|
||||
self.surface = pygame.surfarray.make_surface(array.swapaxes(0, 1))
|
||||
if self.recording:
|
||||
image.save_to_disk('_out/%08d' % image.frame_number)
|
||||
|
||||
|
||||
|
|
|
@ -166,7 +166,7 @@ class Util(object):
|
|||
destination_surface.blit(surface[0], surface[1], rect, blend_mode)
|
||||
|
||||
@staticmethod
|
||||
def length (v):
|
||||
def length(v):
|
||||
return math.sqrt(v.x**2 + v.y**2 + v.z**2)
|
||||
# ==============================================================================
|
||||
# -- ModuleManager -------------------------------------------------------------
|
||||
|
@ -478,16 +478,15 @@ class MapImage(object):
|
|||
|
||||
# Draw line in front of stop
|
||||
forward_vector = carla.Location(waypoint.transform.get_forward_vector())
|
||||
left_vector = carla.Location(-forward_vector.y, forward_vector.x, forward_vector.z) * waypoint.lane_width/2 * 0.7
|
||||
left_vector = carla.Location(-forward_vector.y, forward_vector.x,
|
||||
forward_vector.z) * waypoint.lane_width / 2 * 0.7
|
||||
|
||||
line = [(waypoint.transform.location + (forward_vector * 1.5) + (left_vector)),
|
||||
(waypoint.transform.location + (forward_vector * 1.5) - (left_vector))]
|
||||
|
||||
|
||||
line_pixel = [world_to_pixel(p) for p in line]
|
||||
pygame.draw.lines(surface, color, True, line_pixel, 2)
|
||||
|
||||
|
||||
|
||||
def lateral_shift(transform, shift):
|
||||
transform.rotation.yaw += 90
|
||||
return transform.location + shift * transform.get_forward_vector()
|
||||
|
@ -501,7 +500,7 @@ class MapImage(object):
|
|||
|
||||
topology = [x[0] for x in carla_map.get_topology()]
|
||||
topology = sorted(topology, key=lambda w: w.transform.location.z)
|
||||
|
||||
|
||||
for waypoint in topology:
|
||||
waypoints = [waypoint]
|
||||
nxt = waypoint.next(precision)[0]
|
||||
|
@ -531,16 +530,15 @@ class MapImage(object):
|
|||
for n, wp in enumerate(waypoints):
|
||||
if (n % 400) == 0:
|
||||
draw_arrow(map_surface, wp.transform)
|
||||
|
||||
|
||||
actors = carla_world.get_actors()
|
||||
stops_transform = [actor.get_transform() for actor in actors if 'stop' in actor.type_id]
|
||||
font_size = world_to_pixel_width(1)
|
||||
font_size = world_to_pixel_width(1)
|
||||
font = pygame.font.SysFont('Arial', font_size, True)
|
||||
font_surface = font.render("STOP", False, COLOR_ALUMINIUM_2)
|
||||
font_surface = pygame.transform.scale(font_surface, (font_surface.get_width(),font_surface.get_height() * 2))
|
||||
font_surface = pygame.transform.scale(font_surface, (font_surface.get_width(), font_surface.get_height() * 2))
|
||||
for stop in stops_transform:
|
||||
draw_stop(map_surface,font_surface, stop)
|
||||
|
||||
draw_stop(map_surface, font_surface, stop)
|
||||
|
||||
def world_to_pixel(self, location, offset=(0, 0)):
|
||||
x = self.scale * self._pixels_per_meter * (location.x - self._world_offset[0])
|
||||
|
@ -594,7 +592,7 @@ class ModuleWorld(object):
|
|||
|
||||
self.traffic_light_surfaces = TrafficLightSurfaces()
|
||||
self.affected_traffic_light = None
|
||||
|
||||
|
||||
# Map info
|
||||
self.map_image = None
|
||||
self.border_round_surface = None
|
||||
|
@ -611,7 +609,7 @@ class ModuleWorld(object):
|
|||
town_map = world.get_map()
|
||||
return (world, town_map)
|
||||
|
||||
except Exception as ex:
|
||||
except RuntimeError as ex:
|
||||
logging.error(ex)
|
||||
exit_game()
|
||||
|
||||
|
@ -701,7 +699,7 @@ class ModuleWorld(object):
|
|||
if self.hero_actor is not None:
|
||||
hero_speed = self.hero_actor.get_velocity()
|
||||
hero_speed_text = 3.6 * math.sqrt(hero_speed.x ** 2 + hero_speed.y ** 2 + hero_speed.z ** 2)
|
||||
|
||||
|
||||
affected_traffic_light_text = 'None'
|
||||
if self.affected_traffic_light is not None:
|
||||
state = self.affected_traffic_light.state
|
||||
|
@ -784,14 +782,13 @@ class ModuleWorld(object):
|
|||
|
||||
return (vehicles, traffic_lights, speed_limits, walkers)
|
||||
|
||||
|
||||
def get_bounding_box(self, actor):
|
||||
bb = actor.trigger_volume.extent
|
||||
corners = [carla.Location(x=-bb.x, y=-bb.y),
|
||||
carla.Location(x=bb.x, y=-bb.y),
|
||||
carla.Location(x=bb.x, y=bb.y),
|
||||
carla.Location(x=-bb.x, y=bb.y),
|
||||
carla.Location(x=-bb.x, y=-bb.y)]
|
||||
carla.Location(x=bb.x, y=-bb.y),
|
||||
carla.Location(x=bb.x, y=bb.y),
|
||||
carla.Location(x=-bb.x, y=bb.y),
|
||||
carla.Location(x=-bb.x, y=-bb.y)]
|
||||
corners = [x + actor.trigger_volume.location for x in corners]
|
||||
t = actor.get_transform()
|
||||
t.transform(corners)
|
||||
|
@ -812,12 +809,12 @@ class ModuleWorld(object):
|
|||
hero_location = self.hero_actor.get_location()
|
||||
d = hero_location.distance(transformed_tv)
|
||||
s = Util.length(tl.trigger_volume.extent) + Util.length(self.hero_actor.bounding_box.extent)
|
||||
if ( d <= s ):
|
||||
if (d <= s):
|
||||
# Highlight traffic light
|
||||
self.affected_traffic_light = tl
|
||||
srf = self.traffic_light_surfaces.surfaces['h']
|
||||
surface.blit(srf, srf.get_rect(center=pos))
|
||||
|
||||
|
||||
srf = self.traffic_light_surfaces.surfaces[tl.state]
|
||||
surface.blit(srf, srf.get_rect(center=pos))
|
||||
|
||||
|
@ -868,7 +865,7 @@ class ModuleWorld(object):
|
|||
pygame.draw.polygon(surface, color, corners)
|
||||
|
||||
def _render_vehicles(self, surface, list_v, world_to_pixel):
|
||||
|
||||
|
||||
for v in list_v:
|
||||
color = COLOR_SKY_BLUE_0
|
||||
if int(v[0].attributes['number_of_wheels']) == 2:
|
||||
|
@ -886,7 +883,7 @@ class ModuleWorld(object):
|
|||
]
|
||||
v[1].transform(corners)
|
||||
corners = [world_to_pixel(p) for p in corners]
|
||||
pygame.draw.lines(surface, color, False, corners, int(math.ceil(4.0 * self.map_image.scale)))
|
||||
pygame.draw.lines(surface, color, False, corners, int(math.ceil(4.0 * self.map_image.scale)))
|
||||
|
||||
def render_actors(self, surface, vehicles, traffic_lights, speed_limits, walkers):
|
||||
# Static actors
|
||||
|
@ -898,7 +895,6 @@ class ModuleWorld(object):
|
|||
self._render_vehicles(surface, vehicles, self.map_image.world_to_pixel)
|
||||
self._render_walkers(surface, walkers, self.map_image.world_to_pixel)
|
||||
|
||||
|
||||
def clip_surfaces(self, clipping_rect):
|
||||
self.actors_surface.set_clip(clipping_rect)
|
||||
self.vehicle_id_surface.set_clip(clipping_rect)
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
#!/usr/bin/env python
|
||||
#!/usr/bin/env python3
|
||||
|
||||
# Copyright (c) 2019 Intel Labs.
|
||||
# authors: German Ros (german.ros@intel.com)
|
||||
|
@ -19,19 +19,29 @@ Please, make sure you install the following dependencies:
|
|||
|
||||
"""
|
||||
|
||||
# @todo Include this file in the Pylint checks.
|
||||
# pylint: skip-file
|
||||
|
||||
import sys
|
||||
|
||||
|
||||
if sys.version_info[0] < 3:
|
||||
print('This script is only available for Python 3')
|
||||
sys.exit(1)
|
||||
|
||||
|
||||
from tr import tr
|
||||
import argparse
|
||||
import cpuinfo
|
||||
import glob
|
||||
import math
|
||||
import numpy as np
|
||||
import pygame
|
||||
import os
|
||||
import psutil
|
||||
import pygame
|
||||
import shutil
|
||||
import subprocess
|
||||
from tr import tr
|
||||
import threading
|
||||
import glob
|
||||
import os
|
||||
import sys
|
||||
|
||||
try:
|
||||
sys.path.append(glob.glob('**/carla-*%d.%d-%s.egg' % (
|
||||
|
@ -57,10 +67,10 @@ actor_list = ['vehicle.*']
|
|||
|
||||
|
||||
def weathers():
|
||||
list_weathers = [ carla.WeatherParameters.ClearNoon,
|
||||
carla.WeatherParameters.CloudyNoon,
|
||||
carla.WeatherParameters.SoftRainSunset
|
||||
]
|
||||
list_weathers = [carla.WeatherParameters.ClearNoon,
|
||||
carla.WeatherParameters.CloudyNoon,
|
||||
carla.WeatherParameters.SoftRainSunset
|
||||
]
|
||||
|
||||
return list_weathers
|
||||
|
||||
|
@ -68,14 +78,14 @@ def weathers():
|
|||
def define_sensors():
|
||||
list_sensor_specs = []
|
||||
|
||||
sensors00 = [{'type':'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,
|
||||
'width': 300, 'height': 200, 'fov': 100, 'label':'1. cam-300x200'}]
|
||||
sensors00 = [{'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,
|
||||
'width': 300, 'height': 200, 'fov': 100, 'label': '1. cam-300x200'}]
|
||||
|
||||
sensors01 = [{'type':'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,
|
||||
'width': 800, 'height': 600, 'fov': 100, 'label':'2. cam-800x600'}]
|
||||
sensors01 = [{'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,
|
||||
'width': 800, 'height': 600, 'fov': 100, 'label': '2. cam-800x600'}]
|
||||
|
||||
sensors02 = [{'type':'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,
|
||||
'width': 1900, 'height': 1080, 'fov': 100, 'label':'3. cam-1900x1080'}]
|
||||
sensors02 = [{'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,
|
||||
'width': 1900, 'height': 1080, 'fov': 100, 'label': '3. cam-1900x1080'}]
|
||||
|
||||
sensors03 = [{'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,
|
||||
'width': 300, 'height': 200, 'fov': 100, 'label': '4. cam-300x200'},
|
||||
|
@ -107,7 +117,7 @@ class CallBack(object):
|
|||
|
||||
def get_fps(self):
|
||||
with self._lock:
|
||||
return self._current_fps
|
||||
return self._current_fps
|
||||
|
||||
|
||||
def create_ego_vehicle(world, ego_vehicle, spawn_point, list_sensor_spec):
|
||||
|
@ -130,7 +140,10 @@ def create_ego_vehicle(world, ego_vehicle, spawn_point, list_sensor_spec):
|
|||
bp.set_attribute('image_size_y', str(sensor_spec['height']))
|
||||
bp.set_attribute('fov', str(sensor_spec['fov']))
|
||||
sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z'])
|
||||
sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], roll=sensor_spec['roll'], yaw=sensor_spec['yaw'])
|
||||
sensor_rotation = carla.Rotation(
|
||||
pitch=sensor_spec['pitch'],
|
||||
roll=sensor_spec['roll'],
|
||||
yaw=sensor_spec['yaw'])
|
||||
elif sensor_spec['type'].startswith('sensor.lidar'):
|
||||
bp.set_attribute('range', '200')
|
||||
bp.set_attribute('rotation_frequency', '10')
|
||||
|
@ -140,7 +153,10 @@ def create_ego_vehicle(world, ego_vehicle, spawn_point, list_sensor_spec):
|
|||
bp.set_attribute('points_per_second', '500000')
|
||||
|
||||
sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z'])
|
||||
sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], roll=sensor_spec['roll'], yaw=sensor_spec['yaw'])
|
||||
sensor_rotation = carla.Rotation(
|
||||
pitch=sensor_spec['pitch'],
|
||||
roll=sensor_spec['roll'],
|
||||
yaw=sensor_spec['yaw'])
|
||||
elif sensor_spec['type'].startswith('sensor.other.gnss'):
|
||||
sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z'])
|
||||
sensor_rotation = carla.Rotation()
|
||||
|
@ -183,7 +199,7 @@ def run_benchmark(world, sensor_specs_list, number_locations, number_ticks, acto
|
|||
while ticks < number_ticks:
|
||||
_ = world.wait_for_tick(1000.0)
|
||||
if debug:
|
||||
print("== Samples {} / {}".format(ticks+1, number_ticks))
|
||||
print("== Samples {} / {}".format(ticks + 1, number_ticks))
|
||||
|
||||
min_fps = float('inf')
|
||||
for sc in sensors_callback:
|
||||
|
@ -224,11 +240,11 @@ def serialize_records(records, system_specs, filename):
|
|||
list_records = records[sensor_key]
|
||||
for record in list_records:
|
||||
s = "| {} | {} | {} | {} | {:03.2f} | {:03.2f} |\n".format(record['sensors'],
|
||||
record['town'],
|
||||
record['weather'],
|
||||
record['samples'],
|
||||
record['fps_mean'],
|
||||
record['fps_std'])
|
||||
record['town'],
|
||||
record['weather'],
|
||||
record['samples'],
|
||||
record['fps_mean'],
|
||||
record['fps_std'])
|
||||
fd.write(s)
|
||||
|
||||
s = "Table: {}.\n".format(system_specs)
|
||||
|
@ -241,7 +257,7 @@ def get_system_specs():
|
|||
str_system += "CPU {} {}. ".format(cpu_info['brand'], cpu_info['family'])
|
||||
|
||||
memory_info = psutil.virtual_memory()
|
||||
str_system += "{:03.2f} GB RAM memory. ".format(memory_info.total / (1024*1024*1024))
|
||||
str_system += "{:03.2f} GB RAM memory. ".format(memory_info.total / (1024 * 1024 * 1024))
|
||||
|
||||
nvidia_cmd = shutil.which("nvidia-smi")
|
||||
if nvidia_cmd:
|
||||
|
@ -286,7 +302,7 @@ def main(args):
|
|||
record = {'sensors': sensor_str,
|
||||
'weather': weather,
|
||||
'town': town,
|
||||
'samples': number_locations*number_ticks,
|
||||
'samples': number_locations * number_ticks,
|
||||
'fps_mean': mean,
|
||||
'fps_std': std}
|
||||
|
||||
|
@ -310,5 +326,3 @@ if __name__ == '__main__':
|
|||
args = parser.parse_args()
|
||||
|
||||
main(args)
|
||||
|
||||
|
||||
|
|
|
@ -0,0 +1,6 @@
|
|||
future
|
||||
networkx
|
||||
nose2
|
||||
numpy
|
||||
pygame
|
||||
setuptools
|
|
@ -27,7 +27,9 @@ def get_libcarla_extensions():
|
|||
yield os.path.join(root, filename)
|
||||
|
||||
if os.name == "posix":
|
||||
if platform.dist()[0].lower() in ["ubuntu", "debian", "deepin"]:
|
||||
# @todo Replace deprecated method.
|
||||
linux_distro = platform.dist()[0] # pylint: disable=W1505
|
||||
if linux_distro.lower() in ["ubuntu", "debian", "deepin"]:
|
||||
pwd = os.path.dirname(os.path.realpath(__file__))
|
||||
pylib = "libboost_python%d%d.a" % (sys.version_info.major,
|
||||
sys.version_info.minor)
|
||||
|
|
|
@ -21,8 +21,6 @@ except IndexError:
|
|||
import carla
|
||||
|
||||
import argparse
|
||||
import random
|
||||
import time
|
||||
|
||||
|
||||
def main():
|
||||
|
@ -69,6 +67,7 @@ def main():
|
|||
finally:
|
||||
pass
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
||||
try:
|
||||
|
|
|
@ -21,8 +21,6 @@ except IndexError:
|
|||
import carla
|
||||
|
||||
import argparse
|
||||
import random
|
||||
import time
|
||||
|
||||
|
||||
def main():
|
||||
|
@ -67,6 +65,7 @@ def main():
|
|||
finally:
|
||||
pass
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
||||
try:
|
||||
|
|
|
@ -21,8 +21,6 @@ except IndexError:
|
|||
import carla
|
||||
|
||||
import argparse
|
||||
import random
|
||||
import time
|
||||
|
||||
|
||||
def main():
|
||||
|
@ -57,6 +55,7 @@ def main():
|
|||
finally:
|
||||
pass
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
||||
try:
|
||||
|
|
|
@ -4,4 +4,5 @@
|
|||
# This work is licensed under the terms of the MIT license.
|
||||
# For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
# pylint: disable=W0401
|
||||
from .libcarla import *
|
||||
|
|
|
@ -4,4 +4,5 @@
|
|||
# This work is licensed under the terms of the MIT license.
|
||||
# For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
# pylint: disable=W0401
|
||||
from .libcarla.command import *
|
||||
|
|
|
@ -133,6 +133,7 @@ def main():
|
|||
print("Stop recording")
|
||||
client.stop_recorder()
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
||||
try:
|
||||
|
|
|
@ -21,8 +21,6 @@ except IndexError:
|
|||
import carla
|
||||
|
||||
import argparse
|
||||
import random
|
||||
import time
|
||||
|
||||
|
||||
def main():
|
||||
|
@ -75,6 +73,7 @@ def main():
|
|||
finally:
|
||||
pass
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
||||
try:
|
||||
|
|
|
@ -20,7 +20,7 @@ except IndexError:
|
|||
import carla
|
||||
|
||||
|
||||
TESTING_ADDRESS=('localhost', 3654)
|
||||
TESTING_ADDRESS = ('localhost', 3654)
|
||||
|
||||
|
||||
class SmokeTest(unittest.TestCase):
|
||||
|
|
|
@ -4,7 +4,6 @@
|
|||
# This work is licensed under the terms of the MIT license.
|
||||
# For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
import random
|
||||
|
||||
from . import SmokeTest
|
||||
|
||||
|
@ -12,15 +11,3 @@ from . import SmokeTest
|
|||
class TestClient(SmokeTest):
|
||||
def test_version(self):
|
||||
self.assertEqual(self.client.get_client_version(), self.client.get_server_version())
|
||||
|
||||
def test_reload_world(self):
|
||||
map_name = self.client.get_world().get_map().name
|
||||
world = self.client.reload_world()
|
||||
self.assertEqual(map_name, world.get_map().name)
|
||||
|
||||
def test_load_all_maps(self):
|
||||
map_names = list(self.client.get_available_maps())
|
||||
random.shuffle(map_names)
|
||||
for map_name in map_names:
|
||||
world = self.client.load_world(map_name)
|
||||
self.assertEqual(map_name.split('/')[-1], world.get_map().name)
|
||||
|
|
|
@ -0,0 +1,49 @@
|
|||
# Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma de
|
||||
# Barcelona (UAB).
|
||||
#
|
||||
# This work is licensed under the terms of the MIT license.
|
||||
# For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
import carla
|
||||
import random
|
||||
|
||||
from . import SmokeTest
|
||||
|
||||
|
||||
class TestMap(SmokeTest):
|
||||
def test_reload_world(self):
|
||||
map_name = self.client.get_world().get_map().name
|
||||
world = self.client.reload_world()
|
||||
self.assertEqual(map_name, world.get_map().name)
|
||||
|
||||
def test_load_all_maps(self):
|
||||
map_names = list(self.client.get_available_maps())
|
||||
random.shuffle(map_names)
|
||||
for map_name in map_names:
|
||||
if map_name != '/Game/Carla/Maps/BaseMap/BaseMap':
|
||||
print(map_name)
|
||||
world = self.client.load_world(map_name)
|
||||
m = world.get_map()
|
||||
self.assertEqual(map_name.split('/')[-1], m.name)
|
||||
self._check_map(m)
|
||||
|
||||
def _check_map(self, m):
|
||||
for spawn_point in m.get_spawn_points():
|
||||
waypoint = m.get_waypoint(spawn_point.location, project_to_road=False)
|
||||
self.assertIsNotNone(waypoint)
|
||||
topology = m.get_topology()
|
||||
self.assertGreater(len(topology), 0)
|
||||
waypoints = list(m.generate_waypoints(2))
|
||||
self.assertGreater(len(waypoints), 0)
|
||||
random.shuffle(waypoints)
|
||||
for waypoint in waypoints[:200]:
|
||||
for _ in range(0, 20):
|
||||
self.assertGreaterEqual(waypoint.lane_width, 0.0)
|
||||
_ = waypoint.get_right_lane()
|
||||
_ = waypoint.get_left_lane()
|
||||
next_waypoints = waypoint.next(4)
|
||||
if not next_waypoints:
|
||||
break
|
||||
waypoint = random.choice(next_waypoints)
|
||||
_ = m.transform_to_geolocation(carla.Location())
|
||||
self.assertTrue(str(m.to_opendrive()))
|
|
@ -30,7 +30,6 @@ class TestSynchronousMode(SmokeTest):
|
|||
self.world = None
|
||||
super(TestSynchronousMode, self).tearDown()
|
||||
|
||||
|
||||
def test_camera_on_synchronous_mode(self):
|
||||
cam_bp = self.world.get_blueprint_library().find('sensor.camera.rgb')
|
||||
t = carla.Transform(carla.Location(z=10))
|
||||
|
|
|
@ -77,7 +77,7 @@ class TestVehiclePhysicsControl(unittest.TestCase):
|
|||
wheels=wheels)
|
||||
|
||||
error = .001
|
||||
for i in range(0,len(torque_curve)):
|
||||
for i in range(0, len(torque_curve)):
|
||||
self.assertTrue(abs(pc.torque_curve[i].x - torque_curve[i][0]) <= error)
|
||||
self.assertTrue(abs(pc.torque_curve[i].y - torque_curve[i][1]) <= error)
|
||||
|
||||
|
@ -98,11 +98,11 @@ class TestVehiclePhysicsControl(unittest.TestCase):
|
|||
self.assertTrue(abs(pc.center_of_mass.y - 1) <= error)
|
||||
self.assertTrue(abs(pc.center_of_mass.z - 1) <= error)
|
||||
|
||||
for i in range(0,len(steering_curve)):
|
||||
for i in range(0, len(steering_curve)):
|
||||
self.assertTrue(abs(pc.steering_curve[i].x - steering_curve[i].x) <= error)
|
||||
self.assertTrue(abs(pc.steering_curve[i].y - steering_curve[i].y) <= error)
|
||||
|
||||
for i in range(0,len(wheels)):
|
||||
for i in range(0, len(wheels)):
|
||||
self.assertTrue(abs(pc.wheels[i].tire_friction - wheels[i].tire_friction) <= error)
|
||||
self.assertTrue(abs(pc.wheels[i].damping_rate - wheels[i].damping_rate) <= error)
|
||||
self.assertTrue(abs(pc.wheels[i].steer_angle - wheels[i].steer_angle) <= error)
|
||||
|
|
|
@ -50,11 +50,12 @@ def main():
|
|||
# at random.
|
||||
bp = random.choice(blueprint_library.filter('vehicle'))
|
||||
|
||||
# A blueprint contains the list of attributes that define a vehicle
|
||||
# A blueprint contains the list of attributes that define a vehicle's
|
||||
# instance, we can read them and modify some of them. For instance,
|
||||
# let's randomize its color.
|
||||
color = random.choice(bp.get_attribute('color').recommended_values)
|
||||
bp.set_attribute('color', color)
|
||||
if bp.has_attribute('color'):
|
||||
color = random.choice(bp.get_attribute('color').recommended_values)
|
||||
bp.set_attribute('color', color)
|
||||
|
||||
# Now we need to give an initial transform to the vehicle. We choose a
|
||||
# random transform from the list of recommended spawn points of the map.
|
||||
|
@ -99,7 +100,7 @@ def main():
|
|||
# vehicles.
|
||||
transform.location += carla.Location(x=40, y=-3.2)
|
||||
transform.rotation.yaw = -180.0
|
||||
for x in range(0, 10):
|
||||
for _ in range(0, 10):
|
||||
transform.location.x += 8.0
|
||||
|
||||
bp = random.choice(blueprint_library.filter('vehicle'))
|
||||
|
|
|
@ -22,11 +22,18 @@ elif os.name == 'posix':
|
|||
|
||||
|
||||
def main():
|
||||
if(args.force):
|
||||
generate_all_maps_but_list([])
|
||||
else:
|
||||
maps = get_map_names()
|
||||
generate_all_maps_but_list(maps)
|
||||
try:
|
||||
args = parse_arguments()
|
||||
if(args.force):
|
||||
generate_all_maps_but_list([], args)
|
||||
else:
|
||||
maps = get_map_names()
|
||||
generate_all_maps_but_list(maps, args)
|
||||
dirname = os.path.dirname(os.path.abspath(__file__))
|
||||
relative_path = os.path.join(dirname, "..", "..", "Unreal", "CarlaUE4", "Content", "Carla", "ExportedMaps")
|
||||
print('Map(s) exported to %s' % os.path.abspath(relative_path))
|
||||
finally:
|
||||
print('\ndone.')
|
||||
|
||||
|
||||
def get_map_names():
|
||||
|
@ -38,7 +45,8 @@ def get_map_names():
|
|||
maps.append(filename)
|
||||
return maps
|
||||
|
||||
def generate_all_maps_but_list(existent_maps):
|
||||
|
||||
def generate_all_maps_but_list(existent_maps, args):
|
||||
map_name = ""
|
||||
dirname = os.getcwd()
|
||||
fbx_place = os.path.join(dirname, "..", "..", "RoadRunnerFiles")
|
||||
|
@ -48,15 +56,16 @@ def generate_all_maps_but_list(existent_maps):
|
|||
if not any(ext in "%s.umap" % map_name for ext in existent_maps):
|
||||
print("Found map in fbx folder: %s" % map_name)
|
||||
import_assets_commandlet(map_name)
|
||||
#move_uassets(map_name)
|
||||
# move_uassets(map_name)
|
||||
print("Generating map asset for %s" % map_name)
|
||||
generate_map(map_name)
|
||||
generate_map(map_name, args)
|
||||
print("Cleaning up directories")
|
||||
cleanup_assets(map_name)
|
||||
print("Finished %s" % map_name)
|
||||
else:
|
||||
print("WARNING: Found %s map in Content folder, skipping. Use \"--force\" to override\n" % map_name)
|
||||
|
||||
|
||||
def parse_arguments():
|
||||
argparser = argparse.ArgumentParser(
|
||||
description=__doc__)
|
||||
|
@ -78,7 +87,7 @@ def parse_arguments():
|
|||
|
||||
def cleanup_assets(map_name):
|
||||
dirname = os.getcwd()
|
||||
content_folder = os.path.join(dirname, "..", "..", "Unreal", "CarlaUE4" , "Content", "Carla")
|
||||
content_folder = os.path.join(dirname, "..", "..", "Unreal", "CarlaUE4", "Content", "Carla")
|
||||
origin_folder = os.path.join(content_folder, "Static", "Imported", map_name)
|
||||
for filename in os.listdir(origin_folder):
|
||||
if map_name in filename:
|
||||
|
@ -94,24 +103,38 @@ def import_assets_commandlet(map_name):
|
|||
commandlet_arguments = "-importSettings=\"%s\" -AllowCommandletRendering -nosourcecontrol -replaceexisting" % import_settings
|
||||
|
||||
file_xodr_origin = os.path.join(dirname, "..", "..", "RoadRunnerFiles", map_name, "%s.xodr" % map_name)
|
||||
file_xodr_dest = os.path.join(dirname, "..", "..", "Unreal", "CarlaUE4", "Content", "Carla", "Maps", "OpenDrive", "%s.xodr" % map_name)
|
||||
file_xodr_dest = os.path.join(
|
||||
dirname,
|
||||
"..",
|
||||
"..",
|
||||
"Unreal",
|
||||
"CarlaUE4",
|
||||
"Content",
|
||||
"Carla",
|
||||
"Maps",
|
||||
"OpenDrive",
|
||||
"%s.xodr" %
|
||||
map_name)
|
||||
|
||||
shutil.copy2(file_xodr_origin, file_xodr_dest)
|
||||
invoke_commandlet(commandlet_name, commandlet_arguments)
|
||||
#Clean up
|
||||
# Clean up
|
||||
os.remove("importsetting.json")
|
||||
|
||||
def generate_map(map_name):
|
||||
|
||||
def generate_map(map_name, args):
|
||||
commandlet_name = "MapProcess"
|
||||
commandlet_arguments = "-mapname=\"%s\"" % map_name
|
||||
if args.usecarlamats:
|
||||
commandlet_arguments += " -use-carla-materials"
|
||||
invoke_commandlet(commandlet_name, commandlet_arguments)
|
||||
# This line might be needed if Epic tells us anything about the current
|
||||
# way of doing the movement. It shouldn't but just in case...
|
||||
|
||||
|
||||
#This line might be needed if Epic tells us anything about the current way of doing the movement. It shouldn't but just in case...
|
||||
def move_uassets(map_name):
|
||||
dirname = os.getcwd()
|
||||
content_folder = os.path.join(dirname, "..", "..", "Unreal", "CarlaUE4" , "Content", "Carla")
|
||||
content_folder = os.path.join(dirname, "..", "..", "Unreal", "CarlaUE4", "Content", "Carla")
|
||||
origin_folder = os.path.join(content_folder, "Static", map_name)
|
||||
dest_path = ""
|
||||
src_path = ""
|
||||
|
@ -135,7 +158,6 @@ def move_uassets(map_name):
|
|||
os.rename(src_path, dest_path)
|
||||
|
||||
|
||||
|
||||
def invoke_commandlet(name, arguments):
|
||||
ue4_path = os.environ['UE4_ROOT']
|
||||
dirname = os.getcwd()
|
||||
|
@ -154,41 +176,34 @@ def generate_json(map_name, json_file):
|
|||
file_names.append(fbx_path)
|
||||
|
||||
import_settings.append({
|
||||
"bImportMesh": 1,
|
||||
"bConvertSceneUnit": 1,
|
||||
"bConvertScene": 1,
|
||||
"bCombineMeshes": 1,
|
||||
"bImportTextures": 1,
|
||||
"bImportMaterials": 1,
|
||||
"bRemoveDegenerates":1,
|
||||
"AnimSequenceImportData": {},
|
||||
"SkeletalMeshImportData": {},
|
||||
"TextureImportData": {},
|
||||
"StaticMeshImportData": {
|
||||
"bImportMesh": 1,
|
||||
"bConvertSceneUnit": 1,
|
||||
"bConvertScene": 1,
|
||||
"bCombineMeshes": 1,
|
||||
"bImportTextures": 1,
|
||||
"bImportMaterials": 1,
|
||||
"bRemoveDegenerates": 1,
|
||||
"bAutoGenerateCollision": 0,
|
||||
"bCombineMeshes":0
|
||||
"AnimSequenceImportData": {},
|
||||
"SkeletalMeshImportData": {},
|
||||
"TextureImportData": {},
|
||||
"StaticMeshImportData": {
|
||||
"bRemoveDegenerates": 1,
|
||||
"bAutoGenerateCollision": 0,
|
||||
"bCombineMeshes": 0
|
||||
}
|
||||
})
|
||||
dest_path = "/Game/Carla/Static/Imported/%s" % map_name
|
||||
import_groups.append({
|
||||
"ImportSettings": import_settings,
|
||||
"FactoryName": "FbxFactory",
|
||||
"DestinationPath": dest_path,
|
||||
"bReplaceExisting": "true",
|
||||
"FileNames": file_names
|
||||
"ImportSettings": import_settings,
|
||||
"FactoryName": "FbxFactory",
|
||||
"DestinationPath": dest_path,
|
||||
"bReplaceExisting": "true",
|
||||
"FileNames": file_names
|
||||
})
|
||||
fh.write(json.dumps({"ImportGroups": import_groups}))
|
||||
fh.close()
|
||||
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
try:
|
||||
args = parse_arguments()
|
||||
main()
|
||||
dirname = os.path.dirname(os.path.abspath(__file__))
|
||||
relative_path = os.path.join(dirname, "..", "..", "Unreal", "CarlaUE4", "Content", "Carla", "ExportedMaps")
|
||||
print('Map(s) exported to %s' % os.path.abspath(relative_path))
|
||||
finally:
|
||||
print('\ndone.')
|
||||
|
||||
main()
|
||||
|
|
|
@ -24,15 +24,13 @@ except IndexError:
|
|||
pass
|
||||
|
||||
import carla
|
||||
import logging
|
||||
import random
|
||||
|
||||
|
||||
def get_scene_layout(world, carla_map):
|
||||
def get_scene_layout(carla_map):
|
||||
"""
|
||||
Function to extract the full scene layout to be used as a full scene description to be
|
||||
given to the user
|
||||
:param world: the world object from CARLA
|
||||
:return: a dictionary describing the scene.
|
||||
"""
|
||||
|
||||
|
|
|
@ -22,7 +22,6 @@ import carla
|
|||
|
||||
import math
|
||||
import random
|
||||
import time
|
||||
|
||||
|
||||
def get_transform(vehicle_location, angle, d=6.4):
|
||||
|
|
|
@ -4,7 +4,6 @@ CARLA Simulator
|
|||
[![Build Status](https://travis-ci.org/carla-simulator/carla.svg?branch=master)](https://travis-ci.org/carla-simulator/carla)
|
||||
[![Documentation](https://readthedocs.org/projects/carla/badge/?version=latest)](http://carla.readthedocs.io)
|
||||
|
||||
|
||||
[![carla.org](Docs/img/btn/web.png)](http://carla.org)
|
||||
[![download](Docs/img/btn/download.png)](https://github.com/carla-simulator/carla/blob/master/Docs/download.md)
|
||||
[![documentation](Docs/img/btn/docs.png)](http://carla.readthedocs.io)
|
||||
|
@ -25,6 +24,8 @@ If you want to benchmark your model in the same conditions as in our CoRL’17
|
|||
paper, check out
|
||||
[Benchmarking](https://github.com/carla-simulator/driving-benchmarks).
|
||||
|
||||
[**Get CARLA overnight build**](http://158.109.9.218:8080/job/carla/job/master/25/artifact/Dist/CARLA_eff21e2.tar.gz)
|
||||
|
||||
|
||||
## CARLA Ecosystem
|
||||
Repositories associated to the CARLA simulation platform:
|
||||
|
|
|
@ -220,13 +220,25 @@ void ACarlaWheeledVehicle::ApplyVehiclePhysicsControl(const FVehiclePhysicsContr
|
|||
Vehicle4W->SteeringCurve.EditorCurveData = PhysicsControl.SteeringCurve;
|
||||
|
||||
// Wheels Setup
|
||||
for (int32 i = 0; i < PhysicsControl.Wheels.Num(); ++i)
|
||||
TArray<FWheelSetup> NewWheelSetups = Vehicle4W->WheelSetups;
|
||||
|
||||
for (int32 i = 0; i < Vehicle4W->WheelSetups.Num(); ++i)
|
||||
{
|
||||
Vehicle4W->Wheels[i]->DampingRate = PhysicsControl.Wheels[i].DampingRate;
|
||||
Vehicle4W->Wheels[i]->SteerAngle = PhysicsControl.Wheels[i].SteerAngle;
|
||||
Vehicle4W->Wheels[i]->GetWheelSetup().bDisableSteering = PhysicsControl.Wheels[i].bDisableSteering;
|
||||
Vehicle4W->Wheels[i]->TireConfig->SetFrictionScale(PhysicsControl.Wheels[i].TireFriction);
|
||||
UVehicleWheel *Wheel = NewWheelSetups[i].WheelClass.GetDefaultObject();
|
||||
|
||||
Wheel->DampingRate = PhysicsControl.Wheels[i].DampingRate;
|
||||
Wheel->SteerAngle = PhysicsControl.Wheels[i].SteerAngle;
|
||||
NewWheelSetups[i].bDisableSteering = PhysicsControl.Wheels[i].bDisableSteering;
|
||||
|
||||
// Assigning new tire config
|
||||
Wheel->TireConfig = NewObject<UTireConfig>();
|
||||
|
||||
// Setting a new value to friction
|
||||
Wheel->TireConfig->SetFrictionScale(PhysicsControl.Wheels[i].TireFriction);
|
||||
|
||||
}
|
||||
|
||||
Vehicle4W->WheelSetups = NewWheelSetups;
|
||||
|
||||
Vehicle4W->RecreatePhysicsState();
|
||||
}
|
||||
|
|
17
Update.sh
17
Update.sh
|
@ -46,7 +46,8 @@ pushd "$SCRIPT_DIR" >/dev/null
|
|||
|
||||
CONTENT_FOLDER=$SCRIPT_DIR/Unreal/CarlaUE4/Content/Carla
|
||||
|
||||
CONTENT_GDRIVE_ID=$(tac $SCRIPT_DIR/Util/ContentVersions.txt | egrep -m 1 . | rev | cut -d' ' -f1 | rev)
|
||||
CONTENT_ID=$(tac $SCRIPT_DIR/Util/ContentVersions.txt | egrep -m 1 . | rev | cut -d' ' -f1 | rev)
|
||||
CONTENT_LINK=http://carla-assets-internal.s3.amazonaws.com/Content/${CONTENT_ID}.tar.gz
|
||||
|
||||
VERSION_FILE=${CONTENT_FOLDER}/.version
|
||||
|
||||
|
@ -57,11 +58,17 @@ function download_content {
|
|||
fi
|
||||
mkdir -p $CONTENT_FOLDER
|
||||
mkdir -p Content
|
||||
./Util/download_from_gdrive.py $CONTENT_GDRIVE_ID Content.tar.gz
|
||||
if hash aria2c 2>/dev/null; then
|
||||
echo -e "${CONTENT_LINK}\n\tout=Content.tar.gz" > .aria2c.input
|
||||
aria2c -j16 -x16 --input-file=.aria2c.input
|
||||
rm -f .aria2c.input
|
||||
else
|
||||
wget ${CONTENT_LINK} Content.tar.gz
|
||||
fi
|
||||
tar -xvzf Content.tar.gz -C Content
|
||||
rm Content.tar.gz
|
||||
mv Content/* $CONTENT_FOLDER
|
||||
echo "$CONTENT_GDRIVE_ID" > "$VERSION_FILE"
|
||||
echo "$CONTENT_ID" > "$VERSION_FILE"
|
||||
echo "Content updated successfully."
|
||||
}
|
||||
|
||||
|
@ -72,7 +79,7 @@ function download_content {
|
|||
if $SKIP_DOWNLOAD ; then
|
||||
echo "Skipping 'Content' update. Please manually download the package from"
|
||||
echo
|
||||
echo " https://drive.google.com/open?id=$CONTENT_GDRIVE_ID"
|
||||
echo " ${CONTENT_LINK}"
|
||||
echo
|
||||
echo "and extract it under Unreal/CarlaUE4/Content/Carla."
|
||||
exit 0
|
||||
|
@ -81,7 +88,7 @@ fi
|
|||
if [[ -d "$CONTENT_FOLDER/.git" ]]; then
|
||||
echo "Using git version of 'Content', skipping update."
|
||||
elif [[ -f "$CONTENT_FOLDER/.version" ]]; then
|
||||
if [ "$CONTENT_GDRIVE_ID" == `cat $VERSION_FILE` ]; then
|
||||
if [ "$CONTENT_ID" == `cat $VERSION_FILE` ]; then
|
||||
echo "Content is up-to-date."
|
||||
else
|
||||
download_content
|
||||
|
|
|
@ -164,7 +164,7 @@ rem ============================================================================
|
|||
FOR /F "tokens=2" %%i in (%VERSION_FILE%) do (
|
||||
set HASH=%%i
|
||||
)
|
||||
set URL=https://drive.google.com/open?id=%HASH%
|
||||
set URL=http://carla-assets-internal.s3.amazonaws.com/Content/%HASH%.tar.gz
|
||||
|
||||
FOR /F "tokens=1 delims=:" %%i in (%VERSION_FILE%) do (
|
||||
set ASSETS_VERSION=%%i
|
||||
|
|
|
@ -255,6 +255,27 @@
|
|||
"shell_cmd": "CARLA_BUILD_NO_COLOR=true make clean"
|
||||
}
|
||||
},
|
||||
{
|
||||
"name": "CARLA - Pylint all",
|
||||
"working_dir": "${project_path}/..",
|
||||
"file_regex": "^([^\n:]*):(-?[0-9]+):?(-?[0-9]+)?:? (.*)$",
|
||||
"syntax": "Packages/Makefile/Make Output.sublime-syntax",
|
||||
"linux":
|
||||
{
|
||||
"shell_cmd": "shopt -s globstar; pylint -rn --msg-template='{path}:{line}:{column}: {msg_id}: {msg}' --disable=R,C --rcfile=PythonAPI/.pylintrc PythonAPI/**/*.py"
|
||||
}
|
||||
},
|
||||
{
|
||||
"name": "CARLA - Pylint this file",
|
||||
"selector": "source.python",
|
||||
"working_dir": "${project_path}/..",
|
||||
"file_regex": "^([^\n:]*):([0-9]+):?([0-9]+)?:? (.*)$",
|
||||
"syntax": "Packages/Makefile/Make Output.sublime-syntax",
|
||||
"linux":
|
||||
{
|
||||
"shell_cmd": "pylint -rn --msg-template='{path}:{line}:{column}: {msg_id}: {msg}' --disable=R,C --rcfile=PythonAPI/.pylintrc ${file}"
|
||||
}
|
||||
},
|
||||
{
|
||||
"name": "CARLA - Prettify this file",
|
||||
"working_dir": "${project_path}/..",
|
||||
|
|
|
@ -2,7 +2,9 @@
|
|||
# in the list it's picked up by the Setup.sh script to download the last version
|
||||
# of the contents.
|
||||
#
|
||||
# You can direct download with https://drive.google.com/open?id=PUT_FILE_ID_HERE
|
||||
# You can download it directly from
|
||||
#
|
||||
# https://drive.google.com/open?id=PUT_FILE_ID_HERE
|
||||
|
||||
0.5.4: 0B2HFV-VuKn3PYUFFanlmZ2VMTW8
|
||||
0.6.0: 1Gw8sw01hDEV4FtpHEZZwvS-6XN0jmaLT
|
||||
|
@ -18,3 +20,11 @@
|
|||
0.9.2: 1RKRGB22U5t80q4zwYXBJvxQXhzNjaaDf
|
||||
0.9.3: 1jJlStNHpey62CrMkWVfmtQcJGO7PaD0R
|
||||
0.9.4: 10Tc0DMXpfH7W28zwagXsVTjpkhGx3Klz
|
||||
|
||||
# Newer asset Content is stored in AWS.
|
||||
#
|
||||
# You can download it directly from
|
||||
#
|
||||
# http://carla-assets-internal.s3.amazonaws.com/Content/PUT_FILE_ID_HERE.tar.gz
|
||||
|
||||
Latest: 20190319_7f836a8
|
||||
|
|
|
@ -14,9 +14,10 @@ import sys
|
|||
|
||||
import requests
|
||||
|
||||
|
||||
def sizeof_fmt(num, suffix='B'):
|
||||
# https://stackoverflow.com/a/1094933/5308925
|
||||
for unit in ['','K','M','G','T','P','E','Z']:
|
||||
for unit in ['', 'K', 'M', 'G', 'T', 'P', 'E', 'Z']:
|
||||
if abs(num) < 1000.0:
|
||||
return "%3.2f%s%s" % (num, unit, suffix)
|
||||
num /= 1000.0
|
||||
|
@ -39,7 +40,7 @@ def download_file_from_google_drive(id, destination):
|
|||
|
||||
with open(destination, "wb") as f:
|
||||
for chunk in response.iter_content(chunk_size):
|
||||
if chunk: # filter out keep-alive new chunks
|
||||
if chunk: # filter out keep-alive new chunks
|
||||
f.write(chunk)
|
||||
written_size += chunk_size
|
||||
print_status(destination, written_size)
|
||||
|
|
|
@ -3,7 +3,7 @@ repo_url: https://github.com/carla-simulator/carla
|
|||
docs_dir: Docs
|
||||
theme: readthedocs
|
||||
|
||||
pages:
|
||||
nav:
|
||||
- Home: 'index.md'
|
||||
- Quick start:
|
||||
- 'Getting started': 'getting_started.md'
|
||||
|
|
Loading…
Reference in New Issue