Improve Python examples

This commit is contained in:
nsubiron 2018-10-09 18:04:50 +02:00
parent a901cccb07
commit f8592fb98c
5 changed files with 484 additions and 289 deletions

View File

@ -1,114 +0,0 @@
#!/usr/bin/env python
import sys
sys.path.append(
'PythonAPI/carla-0.9.0-py%d.%d-linux-x86_64.egg' % (sys.version_info.major,
sys.version_info.minor))
import carla
import os
import random
import time
# This function is here because this functionality haven't been ported to the
# new API yet.
def save_to_disk(image):
"""Save this image to disk (requires PIL installed)."""
filename = '_images/{:0>6d}_{:s}.png'.format(image.frame_number, image.type)
try:
from PIL import Image as PImage
except ImportError:
raise RuntimeError(
'cannot import PIL, make sure pillow package is installed')
image = PImage.frombytes(
mode='RGBA',
size=(image.width, image.height),
data=image.raw_data,
decoder_name='raw')
color = image.split()
image = PImage.merge("RGB", color[2::-1])
folder = os.path.dirname(filename)
if not os.path.isdir(folder):
os.makedirs(folder)
image.save(filename)
def main(add_a_camera, enable_autopilot):
client = carla.Client('localhost', 2000)
client.set_timeout(2.0)
print('client version: %s' % client.get_client_version())
print('server version: %s' % client.get_server_version())
world = client.get_world()
blueprint_library = world.get_blueprint_library()
vehicle_blueprints = blueprint_library.filter('vehicle')
actor_list = []
try:
while True:
bp = random.choice(vehicle_blueprints)
if bp.contains_attribute('number_of_wheels'):
n = bp.get_attribute('number_of_wheels')
print('spawning vehicle %r with %d wheels' % (bp.id, n))
color = random.choice(bp.get_attribute('color').recommended_values)
bp.set_attribute('color', color)
transform = carla.Transform(
carla.Location(x=180.0, y=199.0, z=40.0),
carla.Rotation(yaw=0.0))
vehicle = world.try_spawn_actor(bp, transform)
if vehicle is None:
continue
actor_list.append(vehicle)
print(vehicle)
if add_a_camera:
add_a_camera = False
camera_bp = blueprint_library.find('sensor.camera')
# camera_bp.set_attribute('post_processing', 'Depth')
camera_transform = carla.Transform(carla.Location(x=0.4, y=0.0, z=1.4))
camera = world.spawn_actor(camera_bp, camera_transform, attach_to=vehicle)
camera.listen(save_to_disk)
if enable_autopilot:
vehicle.set_autopilot()
else:
vehicle.apply_control(carla.VehicleControl(throttle=1.0, steer=-1.0))
time.sleep(3)
print('vehicle at %s' % vehicle.get_location())
vehicle.set_location(carla.Location(x=220, y=199, z=38))
print('is now at %s' % vehicle.get_location())
time.sleep(2)
finally:
for actor in actor_list:
actor.destroy()
if __name__ == '__main__':
main(add_a_camera=False, enable_autopilot=True)

View File

@ -21,45 +21,69 @@ Use ARROWS or WASD keys for control.
Space : hand-brake
P : toggle autopilot
STARTING in a moment...
"""
TAB : change camera position
` : next camera sensor
[1-9] : change to camera sensor [1-9]
###############################################################################
R : toggle recording images to disk
H/? : toggle help
ESC : quit
"""
from __future__ import print_function
import sys
import os
if os.name == "posix":
sys.path.append(
'PythonAPI/carla-0.9.0-py%d.%d-linux-x86_64.egg' % (sys.version_info.major,
sys.version_info.minor))
elif os.name == "nt":
sys.path.append(
'PythonAPI/carla-0.9.0-py%d.%d-win-amd64.egg' % (sys.version_info.major,
sys.version_info.minor))
else:
raise NotImplementedError
# ==============================================================================
# -- find carla module ---------------------------------------------------------
# ==============================================================================
import glob
import os
import sys
try:
sys.path.append(glob.glob('**/carla-*%d.%d-%s.egg' % (
sys.version_info.major,
sys.version_info.minor,
'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0])
except IndexError:
pass
# ==============================================================================
# -- imports -------------------------------------------------------------------
# ==============================================================================
import carla
from carla import ColorConverter as cc
import argparse
import logging
import random
import time
###############################################################################
import weakref
try:
import pygame
from pygame.locals import KMOD_CTRL
from pygame.locals import KMOD_SHIFT
from pygame.locals import K_0
from pygame.locals import K_9
from pygame.locals import K_BACKQUOTE
from pygame.locals import K_DOWN
from pygame.locals import K_ESCAPE
from pygame.locals import K_LEFT
from pygame.locals import K_RIGHT
from pygame.locals import K_SLASH
from pygame.locals import K_SPACE
from pygame.locals import K_TAB
from pygame.locals import K_UP
from pygame.locals import K_a
from pygame.locals import K_d
from pygame.locals import K_h
from pygame.locals import K_p
from pygame.locals import K_q
from pygame.locals import K_r
@ -73,208 +97,363 @@ try:
except ImportError:
raise RuntimeError('cannot import numpy, make sure numpy package is installed')
###############################################################################
WINDOW_WIDTH = 800
WINDOW_HEIGHT = 600
# ==============================================================================
# -- World ---------------------------------------------------------------------
# ==============================================================================
START_POSITION = carla.Transform(carla.Location(x=180.0, y=199.0, z=40.0))
CAMERA_POSITION = carla.Transform(carla.Location(x=0.5, z=1.40))
###############################################################################
class CarlaGame(object):
def __init__(self, args):
self._client = carla.Client(args.host, args.port)
self._client.set_timeout(2000)
class World(object):
def __init__(self, carla_world, hud):
self.hud = hud
blueprint = random.choice(carla_world.get_blueprint_library().filter('vehicle'))
self.vehicle = carla_world.spawn_actor(blueprint, START_POSITION)
self.camera_manager = CameraManager(self.vehicle, self.hud)
self.controller = None
self._display = None
def tick(self, clock):
self.hud.tick(self, clock)
def render(self, display):
self.camera_manager.render(display)
self.hud.render(display)
def destroy(self):
for actor in [self.camera_manager.sensor, self.vehicle]:
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()
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):
for event in pygame.event.get():
if event.type == pygame.QUIT:
return True
elif event.type == pygame.KEYUP:
if self._is_quit_shortcut(event.key):
return True
elif event.key == K_h or (event.key == K_SLASH and pygame.key.get_mods() & KMOD_SHIFT):
world.hud.help.toggle()
elif event.key == K_TAB:
world.camera_manager.toggle_camera()
elif event.key == K_BACKQUOTE:
world.camera_manager.next_sensor()
elif event.key > K_0 and event.key <= K_9:
world.camera_manager.set_sensor(event.key - 1)
elif event.key == K_r:
world.camera_manager.toggle_recording()
elif event.key == K_q:
self._control.reverse = not self._control.reverse
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'))
if not self._autopilot_enabled:
self._parse_keys(pygame.key.get_pressed(), clock.get_time())
world.vehicle.apply_control(self._control)
def _parse_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]:
self._steer_cache -= steer_increment
elif keys[K_RIGHT] or keys[K_d]:
self._steer_cache += steer_increment
else:
self._steer_cache = 0.0
self._steer_cache = min(0.7, max(-0.7, self._steer_cache))
self._control.steer = round(self._steer_cache, 1)
self._control.brake = 1.0 if keys[K_DOWN] or keys[K_s] else 0.0
self._control.hand_brake = keys[K_SPACE]
@staticmethod
def _is_quit_shortcut(key):
return (key == K_ESCAPE) or (key == K_q and pygame.key.get_mods() & KMOD_CTRL)
# ==============================================================================
# -- HUD -----------------------------------------------------------------------
# ==============================================================================
class HUD(object):
def __init__(self, width, height):
self.dim = (width, height)
font = pygame.font.Font(pygame.font.get_default_font(), 20)
mono = next(x for x in pygame.font.get_fonts() if 'mono' in x) # hope for the best...
mono = pygame.font.match_font(mono, bold=True)
self._font_mono = pygame.font.Font(mono, 14)
self._notifications = FadingText(font, (width, 40), (0, height - 40))
self.help = HelpText(pygame.font.Font(mono, 24), width, height)
self.client_fps = 0
self.server_fps = 0
def tick(self, world, clock):
self.client_fps = clock.get_fps()
self._notifications.tick(world, clock)
def notification(self, text, seconds=2.0):
self._notifications.set_text(text, seconds=seconds)
def error(self, text):
self._notifications.set_text('Error: %s' % text, (255, 0, 0))
def render(self, display):
self._notifications.render(display)
self.help.render(display)
fps_text = 'client: %02d FPS; server: %02d FPS' % (self.client_fps, self.server_fps)
fps = self._font_mono.render(fps_text, True, (60, 60, 60))
display.blit(fps, (6, 4))
# ==============================================================================
# -- FadingText ----------------------------------------------------------------
# ==============================================================================
class FadingText(object):
def __init__(self, font, dim, pos):
self.font = font
self.dim = dim
self.pos = pos
self.seconds_left = 0
self.surface = pygame.Surface(self.dim)
def set_text(self, text, color=(255, 255, 255), seconds=2.0):
text_texture = self.font.render(text, True, color)
self.surface = pygame.Surface(self.dim)
self.seconds_left = seconds
self.surface.fill((0, 0, 0, 0))
self.surface.blit(text_texture, (10, 11))
def tick(self, _, clock):
delta_seconds = 1e-3 * clock.get_time()
self.seconds_left = max(0.0, self.seconds_left - delta_seconds)
self.surface.set_alpha(500.0 * self.seconds_left)
def render(self, display):
display.blit(self.surface, self.pos)
# ==============================================================================
# -- HelpText ------------------------------------------------------------------
# ==============================================================================
class HelpText(object):
def __init__(self, font, width, height):
self.font = font
self.dim = (680, 460)
self.pos = (0.5 * width - 0.5 * self.dim[0], 0.5 * height - 0.5 * self.dim[1])
self.seconds_left = 0
self.surface = pygame.Surface(self.dim)
self.surface.fill((0, 0, 0, 0))
for n, line in enumerate(__doc__.split('\n')):
text_texture = self.font.render(line, True, (255, 255, 255))
self.surface.blit(text_texture, (22, n * 21))
self._render = False
self.surface.set_alpha(220)
def toggle(self):
self._render = not self._render
def render(self, display):
if self._render:
display.blit(self.surface, self.pos)
# ==============================================================================
# -- CameraManager -------------------------------------------------------------
# ==============================================================================
class CameraManager(object):
def __init__(self, parent_actor, hud):
self.sensor = None
self._surface = None
self._parent = parent_actor
self._hud = hud
self._recording = False
self._camera_transforms = [
carla.Transform(carla.Location(x=1.6, z=1.7)),
carla.Transform(carla.Location(x=-4.5, z=2.8), carla.Rotation(pitch=-15))]
self._current_transform = self._camera_transforms[0]
self._sensors = [
['sensor.camera.rgb', cc.None, 'Camera RGB'],
['sensor.camera.depth', cc.None, '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.None, 'Camera Semantic Segmentation (Raw)'],
['sensor.camera.semantic_segmentation', cc.CityScapesPalette, 'Camera Semantic Segmentation (CityScapes Palette)']]
world = self._parent.get_world()
bp_library = world.get_blueprint_library()
for item in self._sensors:
bp = bp_library.find(item[0])
bp.set_attribute('image_size_x', str(hud.dim[0]))
bp.set_attribute('image_size_y', str(hud.dim[1]))
item.append(bp)
self._index = None
self._server_clock = pygame.time.Clock()
self.set_sensor(0)
self._camera = None
self._vehicle = None
def toggle_camera(self):
self._hud.error('not implemented')
self._is_on_reverse = False
self._autopilot_enabled = args.autopilot
def set_sensor(self, index):
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.sensor = self._parent.get_world().spawn_actor(
self._sensors[index][-1],
self._current_transform,
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))
self._hud.notification(self._sensors[index][2])
self._index = index
self.keyTime = {}
self.keyTimeout = 0.3
def next_sensor(self):
self.set_sensor(self._index + 1)
self.steeringTime = 2.0
self.steeringTimeLeft = 0.0
self.steeringTimeRight = 0.0
def toggle_recording(self):
self._recording = not self._recording
self._hud.notification('Recording %s' % ('On' if self._recording else 'Off'))
def lerp(self, t, v0, v1):
if t > 1.0: t = 1.0
return (1.0 - t) * v0 + t * v1
def render(self, display):
if self._surface is not None:
display.blit(self._surface, (0, 0))
def resetVehicle(self):
if self._camera is not None:
self._camera.destroy()
self._camera = None
if self._vehicle is not None:
self._vehicle.destroy()
self._vehicle = None
world = self._client.get_world()
blueprint = random.choice(world.get_blueprint_library().filter('tt'))
cam_blueprint = world.get_blueprint_library().find('sensor.camera')
self._vehicle = world.spawn_actor(blueprint, START_POSITION)
self._camera = world.spawn_actor(cam_blueprint, CAMERA_POSITION, attach_to=self._vehicle)
self._camera.listen(self._parse_image)
def execute(self):
pygame.init()
try:
self._display = pygame.display.set_mode((WINDOW_WIDTH, WINDOW_HEIGHT), pygame.HWSURFACE | pygame.DOUBLEBUF)
logging.debug('pygame started')
self.resetVehicle()
self._vehicle.set_autopilot(self._autopilot_enabled)
while True:
for event in pygame.event.get():
if event.type == pygame.QUIT:
return
self._on_loop()
self._on_render()
finally:
if self._camera is not None:
self._camera.destroy()
self._camera = None
if self._vehicle is not None:
self._vehicle.destroy()
self._vehicle = None
pygame.quit()
def _parse_image(self, image):
@staticmethod
def _parse_image(weak_self, image):
self = weak_self()
if not self:
return
self._server_clock.tick()
self._hud.server_fps = self._server_clock.get_fps()
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))
def _on_loop(self):
autopilot = self._autopilot_enabled
control = self._get_keyboard_control(pygame.key.get_pressed())
if autopilot != self._autopilot_enabled:
self._vehicle.set_autopilot(autopilot)
self._autopilot_enabled = autopilot
if not self._autopilot_enabled:
self._vehicle.apply_control(control)
def _get_keyboard_control(self, keys):
control = carla.VehicleControl()
if keys[K_LEFT] or keys[K_a]:
if self.steeringTimeLeft < 0.00001: self.steeringTimeLeft = time.time() + self.steeringTime
t = 1.0 - (self.steeringTimeLeft - time.time()) / self.steeringTime
control.steer = -(0.2 + self.lerp(t, 0.0, 0.5))
else:
self.steeringTimeLeft = 0.0
if keys[K_RIGHT] or keys[K_d]:
if self.steeringTimeRight < 0.00001: self.steeringTimeRight = time.time() + self.steeringTime
t = 1.0 - (self.steeringTimeRight - time.time()) / self.steeringTime
control.steer = +(0.2 + self.lerp(t, 0.0, 0.5))
else:
self.steeringTimeRight = 0.0
if keys[K_UP] or keys[K_w]:
control.throttle = 1.0
if keys[K_DOWN] or keys[K_s]:
control.brake = 1.0
if keys[K_SPACE]:
control.hand_brake = True
# Interval key press
# These keys can only be pressed each X seconds
if keys[K_q] and not 'K_q' in self.keyTime:
self._is_on_reverse = not self._is_on_reverse
self.keyTime.update(K_q = time.time() + self.keyTimeout)
if keys[K_p] and not 'K_p' in self.keyTime:
self._autopilot_enabled = not self._autopilot_enabled
self.keyTime.update(K_p = time.time() + self.keyTimeout)
# Allow keys to be pressed again
# Delete key from the pressed key dictionary
for key, value in self.keyTime.items():
if value - time.time() <= 0.0:
self.keyTime.pop(key)
break
control.reverse = self._is_on_reverse
return control
def _on_render(self):
if self._surface is not None:
self._display.blit(self._surface, (0, 0))
pygame.display.flip()
if self._recording:
image.save_to_disk('_out/%08d' % image.frame_number)
###############################################################################
# ==============================================================================
# -- game_loop() ---------------------------------------------------------------
# ==============================================================================
def game_loop(args):
pygame.init()
pygame.font.init()
world = None
try:
client = carla.Client(args.host, args.port)
client.set_timeout(2.0)
display = pygame.display.set_mode(
(args.width, args.height),
pygame.HWSURFACE | pygame.DOUBLEBUF)
hud = HUD(args.width, args.height)
world = World(client.get_world(), hud)
controller = KeyboardControl(world, args.autopilot)
clock = pygame.time.Clock()
while True:
clock.tick_busy_loop(60)
if controller.parse_events(world, clock):
return
world.tick(clock)
world.render(display)
pygame.display.flip()
finally:
if world is not None:
world.destroy()
pygame.quit()
# ==============================================================================
# -- main() --------------------------------------------------------------------
# ==============================================================================
def main():
argparser = argparse.ArgumentParser(
description='CARLA Manual Control Client')
argparser.add_argument(
'-v', '--verbose',
action='store_true',
dest='debug',
help='print debug information')
argparser.add_argument(
'--host',
metavar='H',
default='127.0.0.1',
help='IP of the host server (default: localhost)')
help='IP of the host server (default: 127.0.0.1)')
argparser.add_argument(
'-p', '--port',
metavar='P',
default=2000,
type=int,
help='TCP port to listen to (default: 2000)')
argparser.add_argument(
'-a', '--autopilot',
action='store_true',
help='enable autopilot')
argparser.add_argument(
'--res',
metavar='WIDTHxHEIGHT',
default='1280x720',
help='window resolution (default: 1280x720)')
args = argparser.parse_args()
args.width, args.height = [int(x) for x in args.res.split('x')]
log_level = logging.DEBUG if args.debug else logging.INFO
logging.basicConfig(format='%(levelname)s: %(message)s', level=log_level)
logging.info('listening to server %s:%s', args.host, args.port)
print(__doc__)
while True:
try:
game = CarlaGame(args)
game.execute()
break
except Exception as error:
logging.error(error)
time.sleep(1)
if __name__ == '__main__':
try:
main()
game_loop(args)
except KeyboardInterrupt:
print('\nCancelled by user. Bye!')
except Exception as error:
logging.exception(error)
if __name__ == '__main__':
main()

123
PythonAPI/tutorial.py Executable file
View File

@ -0,0 +1,123 @@
#!/usr/bin/env python
import glob
import os
import sys
try:
sys.path.append(glob.glob('**/*%d.%d-%s.egg' % (
sys.version_info.major,
sys.version_info.minor,
'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0])
except IndexError:
pass
import carla
import random
import time
def main():
actor_list = []
# In this tutorial script, we are going to add a vehicle to the simulation
# and let it drive in autopilot. We will also create a camera attached to
# that vehicle, and save all the images generated by the camera to disk.
try:
# First of all, we need to create the client that will send the requests
# to the simulator. Here we'll assume the simulator is accepting
# requests in the localhost at port 2000.
client = carla.Client('localhost', 2000)
client.set_timeout(2.0)
# Once we have a client we can retrieve the world that is currently
# running.
world = client.get_world()
# The world contains the list blueprints that we can use for adding new
# actors into the simulation.
blueprint_library = world.get_blueprint_library()
# Now let's filter all the blueprints of type 'vehicle' and choose one
# at random.
bp = random.choice(blueprint_library.filter('vehicle'))
# A blueprint contains the list of attributes that define a vehicle
# 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)
# Now we need to give an initial transform to the vehicle. This is a
# nice spot in Town01.
transform = carla.Transform(
carla.Location(x=140.0, y=199.0, z=40.0),
carla.Rotation(yaw=0.0))
# So let's tell the world to spawn the vehicle.
vehicle = world.spawn_actor(bp, transform)
# It is important to note that the actors we create won't be destroyed
# unless we call their "destroy" function. If we fail to call "destroy"
# they will stay in the simulation even after we quit the Python script.
# For that reason, we are storing all the actors we create so we can
# destroy them afterwards.
actor_list.append(vehicle)
print('created %s' % vehicle.type_id)
# Let's put the vehicle to drive around.
vehicle.set_autopilot(True)
# Let's add now a "depth" camera attached to the vehicle. Note that the
# transform we give here is now relative to the vehicle.
camera_bp = blueprint_library.find('sensor.camera.depth')
camera_transform = carla.Transform(carla.Location(x=1.5, z=2.4))
camera = world.spawn_actor(camera_bp, camera_transform, attach_to=vehicle)
actor_list.append(camera)
print('created %s' % camera.type_id)
# Now we register the function that will be called each time the sensor
# receives an image. In this example we are saving the image to disk
# converting the pixels to gray-scale.
cc = carla.ColorConverter.LogarithmicDepth
camera.listen(lambda image: image.save_to_disk('_out/%06d.png' % image.frame_number, cc))
# Oh wait, I don't like the location we gave to the vehicle, I'm going
# to move it a bit forward.
location = vehicle.get_location()
location.x += 40
vehicle.set_location(location)
print('moved vehicle to %s' % location)
# But the city now is probably quite empty, let's add a few more
# vehicles.
transform.location += carla.Location(x=40, y=-3.2)
transform.rotation.yaw = -180.0
for x in range(0, 10):
transform.location.x += 8.0
bp = random.choice(blueprint_library.filter('vehicle'))
# This time we are using try_spawn_actor. If the spot is already
# occupied by another object, the function will return None.
npc = world.try_spawn_actor(bp, transform)
if npc is not None:
actor_list.append(npc)
npc.set_autopilot()
print('created %s' % npc.type_id)
time.sleep(5)
finally:
print('destroying actors')
for actor in actor_list:
actor.destroy()
print('done.')
if __name__ == '__main__':
main()

View File

@ -1,17 +1,23 @@
#!/usr/bin/env python
import glob
import os
import sys
sys.path.append(
'PythonAPI/carla-0.9.0-py%d.%d-linux-x86_64.egg' % (sys.version_info.major,
sys.version_info.minor))
try:
sys.path.append(glob.glob('**/*%d.%d-%s.egg' % (
sys.version_info.major,
sys.version_info.minor,
'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0])
except IndexError:
pass
import carla
import math
import time
# Nice spot on Town01.
# Nice spot in Town01.
LOCATION = carla.Location(x=155.5, y=55.8, z=39)

View File

@ -96,10 +96,11 @@ if $DO_COPY_FILES ; then
copy_if_changed "./LICENSE" "${DESTINATION}/LICENSE"
copy_if_changed "./CHANGELOG.md" "${DESTINATION}/CHANGELOG"
copy_if_changed "./Docs/release_readme.md" "${DESTINATION}/README"
copy_if_changed "./Docs/python_api.md" "${DESTINATION}/python_api.md"
# copy_if_changed "./Docs/Example.CarlaSettings.ini" "${DESTINATION}/Example.CarlaSettings.ini"
copy_if_changed "./Util/Docker/Release.Dockerfile" "${DESTINATION}/Dockerfile"
copy_if_changed "./PythonAPI/dist/*.egg" "${DESTINATION}/PythonAPI/"
copy_if_changed "./PythonAPI/example.py" "${DESTINATION}/example.py"
copy_if_changed "./PythonAPI/tutorial.py" "${DESTINATION}/tutorial.py"
copy_if_changed "./PythonAPI/manual_control.py" "${DESTINATION}/manual_control.py"
copy_if_changed "./PythonAPI/vehicle_gallery.py" "${DESTINATION}/vehicle_gallery.py"