Merge pull request #49 from carla-simulator/new_client_api

Fix #32, brand new client API
This commit is contained in:
felipecode 2017-11-24 16:40:04 +01:00 committed by GitHub
commit adecf52043
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
44 changed files with 2327 additions and 1867 deletions

2
.gitignore vendored
View File

@ -18,9 +18,9 @@ Util/Build
*.workspace *.workspace
*CodeCompletionFolders.txt *CodeCompletionFolders.txt
*CodeLitePreProcessor.txt *CodeLitePreProcessor.txt
*_pb2.py
.codelite .codelite
.tags* .tags*
.vs .vs
__pycache__ __pycache__
_images
core core

View File

@ -42,7 +42,8 @@
"settings": "settings":
{ {
"tab_size": 2, "tab_size": 2,
"translate_tabs_to_spaces": true "translate_tabs_to_spaces": true,
"trim_trailing_white_space_on_save": true
}, },
"build_systems": "build_systems":
[ [

View File

@ -34,29 +34,30 @@ To run CARLA as server, see ["Running the server"](#running-the-server) below.
Running the Python client Running the Python client
------------------------- -------------------------
Requires Python 3 with some extra modules installed The "carla" Python module provides a basic API for communicating with the CARLA
server. In the "PythonClient" folder we provide a couple of examples on how to
use this API. We recommend Python 3, but they are also compatible with Python 2.
The basic functionality requires only the protobuf module to be installed
$ sudo apt-get install python3 python3-pip $ sudo apt-get install python3 python3-pip
$ sudo pip3 install protobuf numpy Pillow $ sudo pip3 install protobuf
A sample Python script is provided at `PythonClient/client_example.py`. The However, other operations as handling images require some extra modules, and the
script is well commented explaining how to use the client API. "manual_control.py" example requires pygame
The script can be run and provides basic functionality for controlling the $ sudo pip3 install numpy Pillow pygame
vehicle and saving images to disk. Run the help command to see options available
$ ./carla_example.py --help The script "PythonClient/client_example.py" provides basic functionality for
controlling the vehicle and saving images to disk. Run the help command to see
options available
A second Python script is provided at `PythonClient/carla_manual_control.py`. $ ./client_example.py --help
The script is pygame dependent and serves as an interactive example where the
user controls the car with a keyboard.
$ sudo apt-get install python3-tk The script "PythonClient/manual_control.py" launches a PyGame window with
$ sudo pip3 install pygame matplolib several views and allows to control the vehicle using the WASD keys.
Run the help command to see options available $ ./manual_control.py --help
$ ./carla_manual_control.py --help
Running the server Running the server
------------------ ------------------

View File

@ -33,7 +33,7 @@ collision_pedestrians | float | Collision intensity with pedestrians.
collision_other | float | General collision intensity (everything else but pedestrians and vehicles). collision_other | float | General collision intensity (everything else but pedestrians and vehicles).
intersection_otherlane | float | Percentage of the car invading other lanes. intersection_otherlane | float | Percentage of the car invading other lanes.
intersection_offroad | float | Percentage of the car off-road. intersection_offroad | float | Percentage of the car off-road.
ai_control | Control | Vehicle's AI control that would apply this frame. autopilot_control | Control | Vehicle's autopilot control that would apply this frame.
###### Transform ###### Transform
@ -67,10 +67,10 @@ rectangle) against the map image of the city. These images are generated in the
editor and serialized for runtime use. You can find them too in the release editor and serialized for runtime use. You can find them too in the release
package under the folder "RoadMaps". package under the folder "RoadMaps".
###### AI control ###### Autopilot control
The `ai_control` measurement contains the control values that the in-game AI The `autopilot_control` measurement contains the control values that the in-game
would apply if it were controlling the vehicle. autopilot system would apply as if it were controlling the vehicle.
This is the same structure used to send the vehicle control to the server. This is the same structure used to send the vehicle control to the server.

View File

@ -1,5 +1,5 @@
INSTALL_FOLDER=$(CURDIR)/Unreal/CarlaUE4/Plugins/Carla/CarlaServer INSTALL_FOLDER=$(CURDIR)/Unreal/CarlaUE4/Plugins/Carla/CarlaServer
PYTHON_CLIENT_FOLDER=$(CURDIR)/Util/TestingClient/test PYTHON_CLIENT_FOLDER=$(CURDIR)/PythonClient/test
BASE_BUILD_FOLDER=$(CURDIR)/Util/Build/carlaserver-build BASE_BUILD_FOLDER=$(CURDIR)/Util/Build/carlaserver-build
MY_CMAKE_FOLDER=$(CURDIR)/Util/cmake MY_CMAKE_FOLDER=$(CURDIR)/Util/cmake
MY_CMAKE_FLAGS=-B"$(BUILD_FOLDER)" -DCMAKE_INSTALL_PREFIX="$(INSTALL_FOLDER)" MY_CMAKE_FLAGS=-B"$(BUILD_FOLDER)" -DCMAKE_INSTALL_PREFIX="$(INSTALL_FOLDER)"

View File

@ -1,36 +0,0 @@
[CARLA/Server]
UseNetworking=true
SynchronousMode = false
SendNonPlayerAgentsInfo= true
[CARLA/LevelSettings]
NumberOfVehicles=20
NumberOfPedestrians=30
WeatherId=3
[CARLA/SceneCapture]
Cameras=RGB,DepthMap,Labels
ImageSizeX=800
ImageSizeY=600
CameraFOV=100
CameraPositionX=200
CameraPositionY=0
CameraPositionZ=140
CameraRotationPitch=-15.0
CameraRotationRoll=0
CameraRotationYaw=0
[CARLA/SceneCapture/RGB]
PostProcessing=SceneFinal
CameraPositionY=0
CameraRotationYaw=0
[CARLA/SceneCapture/DepthMap]
PostProcessing=Depth
CameraPositionY=0
CameraRotationYaw=0
[CARLA/SceneCapture/Labels]
PostProcessing=SemanticSegmentation
CameraPositionY=0
CameraRotationYaw=0

View File

@ -1,3 +0,0 @@
from .carla import CARLA
from .protoc import SceneDescription,EpisodeStart,EpisodeReady,Control,Measurements,RequestNewEpisode

View File

@ -1,323 +0,0 @@
#!/usr/bin/env python3
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
# Barcelona (UAB), and the INTEL Visual Computing Lab.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
from __future__ import print_function
from .datastream import DataStream
import socket
import time
import os, signal
import sys
import logging
import struct
import re
from .protoc import *
from . import socket_util
def get_image_resolution(data):
return int(re.search('[\n\r].*ImageSizeX\s*=([^\n\r]*)', data).group(1)),int(re.search('[\n\r].*ImageSizeY\s*=([^\n\r]*)', data).group(1))
class CARLA(object):
"""
Normal instanciation of the class, creating also the thread class responsible for receiving data
"""
def __init__(self,host,port):
self._host = host
self._port = port
logging.debug('selected host %s' % host)
logging.debug('selected port %s' % port)
self._port_control = self._port +2
self._port_stream = self._port +1
# Default start. Keep it as class param for eventual restart
self._image_x =0
self._image_y = 0
self._socket_world = socket_util.pers_connect(self._host ,self._port)
print ('Successfully Connected to Carla Server')
logging.debug("Connected to Unreal Server World Socket")
self._socket_stream = 0
self._socket_control = 0
self._latest_start = 0
self._agent_is_running = False
self._episode_requested = False
self._data_stream = None
logging.debug("Started Unreal Client")
"""
Starting the Player Agent. The image stream port
and the control port
Args:
None
Returns:
None
"""
def startAgent(self):
self._data_stream = DataStream(self._image_x,self._image_y)
logging.debug("Going to Connect Stream and start thread")
# Perform persistent connections, try up to 10 times
try:
self._socket_stream = socket_util.pers_connect(self._host ,self._port_stream)
except Exception:
logging.exception("Attempts to connect Stream all failed, restart...")
self.restart()
self._data_stream.start(self._socket_stream)
logging.debug("Streaming Thread Started")
try:
self._socket_control = socket_util.pers_connect(self._host ,self._port_control)
except Exception:
logging.exception("Attempts to connect Agent all failed, restart ...")
self.restart()
logging.debug("Control Socket Connected")
self._agent_is_running = True
def stopAgent(self):
logging.debug("Going to Stop thread and Disconect Stream")
self._data_stream.stop()
logging.debug("Streaming Thread Stoped")
socket_util.disconnect(self._socket_control)
logging.debug("Control Socket DisConnected")
self._agent_is_running = False
# This function requests a new episode and send the string containing this episode configuration file
def receiveSceneConfiguration(self):
try:
logging.debug("Reading for the scene configuration")
data = socket_util.get_message(self._socket_world)
scene = SceneDescription()
scene.ParseFromString(data)
logging.debug("Received Scene Configuration")
return scene.player_start_spots
except Exception as e:
logging.exception("Server not responing when receiving configuration")
return self.restart()
def requestNewEpisode(self,ini_path=None):
if ini_path == None:
ini_file = self._config_path
else:
ini_file = ini_path
self._config_path = ini_path # We just save the last config file in case the client dies
requestEpisode = RequestNewEpisode()
with open (ini_file, "r") as myfile:
data=myfile.read()
try:
self._image_x,self._image_y = get_image_resolution(data)
except Exception as e:
logging.exception("No image resolution found on config file")
logging.debug("Resolution %d , %d",self._image_x,self._image_y)
logging.debug("Set the Init File")
logging.debug("sent %s" % (data))
requestEpisode.ini_file = data.encode('utf-8')
try:
socket_util.send_message(self._socket_world,requestEpisode)
except Exception as e:
logging.exception("Server not responding when requesting new episode")
self.restart()
else:
logging.debug("Successfully sent the new episode Request")
if self._agent_is_running:
self.stopAgent()
self._episode_requested = True
return self.receiveSceneConfiguration()
def loadConfigurationFile(self,ini_path):
return self.requestNewEpisode(ini_path)
def newEpisode(self,start_index):
# Save the latest new episode positon, just in case of crashes
self._latest_start = start_index
if not self._episode_requested:
positions = self.requestNewEpisode(self._config_path)
scene_init = EpisodeStart()
scene_init.player_start_spot_index = start_index
try:
socket_util.send_message(self._socket_world,scene_init)
except Exception:
logging.exception("Server not responding when trying to send episode start confirmation")
self.restart()
else:
logging.debug("Successfully sent the new episode Message")
episode_ready = EpisodeReady()
episode_ready.ready = False
try:
data = socket_util.get_message(self._socket_world)
logging.debug("Got the episode ready message")
episode_ready.ParseFromString(data)
except Exception:
logging.exception("Server not responding when trying to receive episode reading")
self.restart()
else:
logging.debug("Episode is Ready")
self.startAgent()
self._episode_requested = False
""" Measurements
returns
@game time
@wall time
@player measurements
@non_player_agents : vector with all agents present on the game
@image_data
"""
def getMeasurements(self):
while True:
try:
meas_dict = self._data_stream.get_the_latest_data()
logging.debug("Got A new Measurement")
return meas_dict
except AttributeError:
logging.exception("Unitialized DataStream. Tip: Connect and start an episode before requesting measurements")
return None
except Exception:
logging.exception("Got an empty Measurement")
self.restart()
""" Command contains:
Steering: -1 to 1
Acc : -1 to 1
"""
def sendCommand(self,control):
logging.debug("Send Control Comand : throttle -> %f , steer %f, brake %f, hand_brake %d, gear %d" % (control.throttle,control.steer,control.brake,control.hand_brake,control.reverse))
try:
socket_util.send_message(self._socket_control,control)
except Exception:
logging.exception("Problems on sending the commands... restarting")
self.restart() # the mensage is not resend because it likely lost its relevance.
def restart(self):
logging.debug("Trying to close clients")
self.closeConections()
connected = False
if self._data_stream != None:
self._data_stream._running = False
self._agent_is_running = False
while not connected:
try:
logging.debug("Trying to connect to the world thread")
self._socket_world = socket_util.connect(self._host ,self._port)
connected = True
except Exception:
logging.exception("Couldn't connected ... retry in 10 seconds...")
time.sleep(10)
self._data_stream = DataStream(self._image_x,self._image_y)
positions = self.requestNewEpisode()
self.newEpisode(self._latest_start)
logging.debug("restarted the world connection")
return positions
def stop(self):
self.closeConections()
connected = False
self._data_stream._running = False
self._data_stream = DataStream(self._image_x,self._image_y)
def closeConections(self):
try:
self._socket_world.shutdown(socket.SHUT_RDWR)
self._socket_world.close()
logging.debug("Close world")
except Exception as ex:
logging.exception("Exception on closing Connections")
try:
self._socket_stream.shutdown(socket.SHUT_RDWR)
self._socket_stream.close()
logging.debug("Close Stream")
except Exception as ex:
logging.exception("Exception on closing Connections")
try:
self._socket_control.shutdown(socket.SHUT_RDWR)
self._socket_control.close()
logging.debug("Close Control")
except Exception as ex:
logging.exception("Exception on closing Connections")

View File

@ -0,0 +1,836 @@
# Generated by the protocol buffer compiler. DO NOT EDIT!
# source: carla_server.proto
import sys
_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))
from google.protobuf import descriptor as _descriptor
from google.protobuf import message as _message
from google.protobuf import reflection as _reflection
from google.protobuf import symbol_database as _symbol_database
from google.protobuf import descriptor_pb2
# @@protoc_insertion_point(imports)
_sym_db = _symbol_database.Default()
DESCRIPTOR = _descriptor.FileDescriptor(
name='carla_server.proto',
package='carla_server',
syntax='proto3',
serialized_pb=_b('\n\x12\x63\x61rla_server.proto\x12\x0c\x63\x61rla_server\"+\n\x08Vector3D\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\x12\t\n\x01z\x18\x03 \x01(\x02\"b\n\tTransform\x12(\n\x08location\x18\x01 \x01(\x0b\x32\x16.carla_server.Vector3D\x12+\n\x0borientation\x18\x02 \x01(\x0b\x32\x16.carla_server.Vector3D\"x\n\x07Vehicle\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12*\n\nbox_extent\x18\x02 \x01(\x0b\x32\x16.carla_server.Vector3D\x12\x15\n\rforward_speed\x18\x03 \x01(\x02\"{\n\nPedestrian\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12*\n\nbox_extent\x18\x02 \x01(\x0b\x32\x16.carla_server.Vector3D\x12\x15\n\rforward_speed\x18\x03 \x01(\x02\"\x94\x01\n\x0cTrafficLight\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12/\n\x05state\x18\x02 \x01(\x0e\x32 .carla_server.TrafficLight.State\"\'\n\x05State\x12\t\n\x05GREEN\x10\x00\x12\n\n\x06YELLOW\x10\x01\x12\x07\n\x03RED\x10\x02\"Q\n\x0eSpeedLimitSign\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12\x13\n\x0bspeed_limit\x18\x02 \x01(\x02\"\xe5\x01\n\x05\x41gent\x12\n\n\x02id\x18\x01 \x01(\x07\x12(\n\x07vehicle\x18\x02 \x01(\x0b\x32\x15.carla_server.VehicleH\x00\x12.\n\npedestrian\x18\x03 \x01(\x0b\x32\x18.carla_server.PedestrianH\x00\x12\x33\n\rtraffic_light\x18\x04 \x01(\x0b\x32\x1a.carla_server.TrafficLightH\x00\x12\x38\n\x10speed_limit_sign\x18\x05 \x01(\x0b\x32\x1c.carla_server.SpeedLimitSignH\x00\x42\x07\n\x05\x61gent\"%\n\x11RequestNewEpisode\x12\x10\n\x08ini_file\x18\x01 \x01(\t\"G\n\x10SceneDescription\x12\x33\n\x12player_start_spots\x18\x01 \x03(\x0b\x32\x17.carla_server.Transform\"/\n\x0c\x45pisodeStart\x12\x1f\n\x17player_start_spot_index\x18\x01 \x01(\r\"\x1d\n\x0c\x45pisodeReady\x12\r\n\x05ready\x18\x01 \x01(\x08\"^\n\x07\x43ontrol\x12\r\n\x05steer\x18\x01 \x01(\x02\x12\x10\n\x08throttle\x18\x02 \x01(\x02\x12\r\n\x05\x62rake\x18\x03 \x01(\x02\x12\x12\n\nhand_brake\x18\x04 \x01(\x08\x12\x0f\n\x07reverse\x18\x05 \x01(\x08\"\x8a\x04\n\x0cMeasurements\x12\x1a\n\x12platform_timestamp\x18\x01 \x01(\r\x12\x16\n\x0egame_timestamp\x18\x02 \x01(\r\x12J\n\x13player_measurements\x18\x03 \x01(\x0b\x32-.carla_server.Measurements.PlayerMeasurements\x12.\n\x11non_player_agents\x18\x04 \x03(\x0b\x32\x13.carla_server.Agent\x1a\xc9\x02\n\x12PlayerMeasurements\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12,\n\x0c\x61\x63\x63\x65leration\x18\x03 \x01(\x0b\x32\x16.carla_server.Vector3D\x12\x15\n\rforward_speed\x18\x04 \x01(\x02\x12\x1a\n\x12\x63ollision_vehicles\x18\x05 \x01(\x02\x12\x1d\n\x15\x63ollision_pedestrians\x18\x06 \x01(\x02\x12\x17\n\x0f\x63ollision_other\x18\x07 \x01(\x02\x12\x1e\n\x16intersection_otherlane\x18\x08 \x01(\x02\x12\x1c\n\x14intersection_offroad\x18\t \x01(\x02\x12\x30\n\x11\x61utopilot_control\x18\n \x01(\x0b\x32\x15.carla_server.ControlB\x03\xf8\x01\x01\x62\x06proto3')
)
_TRAFFICLIGHT_STATE = _descriptor.EnumDescriptor(
name='State',
full_name='carla_server.TrafficLight.State',
filename=None,
file=DESCRIPTOR,
values=[
_descriptor.EnumValueDescriptor(
name='GREEN', index=0, number=0,
options=None,
type=None),
_descriptor.EnumValueDescriptor(
name='YELLOW', index=1, number=1,
options=None,
type=None),
_descriptor.EnumValueDescriptor(
name='RED', index=2, number=2,
options=None,
type=None),
],
containing_type=None,
options=None,
serialized_start=538,
serialized_end=577,
)
_sym_db.RegisterEnumDescriptor(_TRAFFICLIGHT_STATE)
_VECTOR3D = _descriptor.Descriptor(
name='Vector3D',
full_name='carla_server.Vector3D',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='x', full_name='carla_server.Vector3D.x', index=0,
number=1, type=2, cpp_type=6, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='y', full_name='carla_server.Vector3D.y', index=1,
number=2, type=2, cpp_type=6, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='z', full_name='carla_server.Vector3D.z', index=2,
number=3, type=2, cpp_type=6, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
],
serialized_start=36,
serialized_end=79,
)
_TRANSFORM = _descriptor.Descriptor(
name='Transform',
full_name='carla_server.Transform',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='location', full_name='carla_server.Transform.location', index=0,
number=1, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='orientation', full_name='carla_server.Transform.orientation', index=1,
number=2, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
],
serialized_start=81,
serialized_end=179,
)
_VEHICLE = _descriptor.Descriptor(
name='Vehicle',
full_name='carla_server.Vehicle',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='transform', full_name='carla_server.Vehicle.transform', index=0,
number=1, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='box_extent', full_name='carla_server.Vehicle.box_extent', index=1,
number=2, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='forward_speed', full_name='carla_server.Vehicle.forward_speed', index=2,
number=3, type=2, cpp_type=6, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
],
serialized_start=181,
serialized_end=301,
)
_PEDESTRIAN = _descriptor.Descriptor(
name='Pedestrian',
full_name='carla_server.Pedestrian',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='transform', full_name='carla_server.Pedestrian.transform', index=0,
number=1, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='box_extent', full_name='carla_server.Pedestrian.box_extent', index=1,
number=2, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='forward_speed', full_name='carla_server.Pedestrian.forward_speed', index=2,
number=3, type=2, cpp_type=6, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
],
serialized_start=303,
serialized_end=426,
)
_TRAFFICLIGHT = _descriptor.Descriptor(
name='TrafficLight',
full_name='carla_server.TrafficLight',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='transform', full_name='carla_server.TrafficLight.transform', index=0,
number=1, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='state', full_name='carla_server.TrafficLight.state', index=1,
number=2, type=14, cpp_type=8, label=1,
has_default_value=False, default_value=0,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
],
extensions=[
],
nested_types=[],
enum_types=[
_TRAFFICLIGHT_STATE,
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
],
serialized_start=429,
serialized_end=577,
)
_SPEEDLIMITSIGN = _descriptor.Descriptor(
name='SpeedLimitSign',
full_name='carla_server.SpeedLimitSign',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='transform', full_name='carla_server.SpeedLimitSign.transform', index=0,
number=1, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='speed_limit', full_name='carla_server.SpeedLimitSign.speed_limit', index=1,
number=2, type=2, cpp_type=6, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
],
serialized_start=579,
serialized_end=660,
)
_AGENT = _descriptor.Descriptor(
name='Agent',
full_name='carla_server.Agent',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='id', full_name='carla_server.Agent.id', index=0,
number=1, type=7, cpp_type=3, label=1,
has_default_value=False, default_value=0,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='vehicle', full_name='carla_server.Agent.vehicle', index=1,
number=2, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='pedestrian', full_name='carla_server.Agent.pedestrian', index=2,
number=3, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='traffic_light', full_name='carla_server.Agent.traffic_light', index=3,
number=4, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='speed_limit_sign', full_name='carla_server.Agent.speed_limit_sign', index=4,
number=5, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
_descriptor.OneofDescriptor(
name='agent', full_name='carla_server.Agent.agent',
index=0, containing_type=None, fields=[]),
],
serialized_start=663,
serialized_end=892,
)
_REQUESTNEWEPISODE = _descriptor.Descriptor(
name='RequestNewEpisode',
full_name='carla_server.RequestNewEpisode',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='ini_file', full_name='carla_server.RequestNewEpisode.ini_file', index=0,
number=1, type=9, cpp_type=9, label=1,
has_default_value=False, default_value=_b("").decode('utf-8'),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
],
serialized_start=894,
serialized_end=931,
)
_SCENEDESCRIPTION = _descriptor.Descriptor(
name='SceneDescription',
full_name='carla_server.SceneDescription',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='player_start_spots', full_name='carla_server.SceneDescription.player_start_spots', index=0,
number=1, type=11, cpp_type=10, label=3,
has_default_value=False, default_value=[],
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
],
serialized_start=933,
serialized_end=1004,
)
_EPISODESTART = _descriptor.Descriptor(
name='EpisodeStart',
full_name='carla_server.EpisodeStart',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='player_start_spot_index', full_name='carla_server.EpisodeStart.player_start_spot_index', index=0,
number=1, type=13, cpp_type=3, label=1,
has_default_value=False, default_value=0,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
],
serialized_start=1006,
serialized_end=1053,
)
_EPISODEREADY = _descriptor.Descriptor(
name='EpisodeReady',
full_name='carla_server.EpisodeReady',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='ready', full_name='carla_server.EpisodeReady.ready', index=0,
number=1, type=8, cpp_type=7, label=1,
has_default_value=False, default_value=False,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
],
serialized_start=1055,
serialized_end=1084,
)
_CONTROL = _descriptor.Descriptor(
name='Control',
full_name='carla_server.Control',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='steer', full_name='carla_server.Control.steer', index=0,
number=1, type=2, cpp_type=6, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='throttle', full_name='carla_server.Control.throttle', index=1,
number=2, type=2, cpp_type=6, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='brake', full_name='carla_server.Control.brake', index=2,
number=3, type=2, cpp_type=6, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='hand_brake', full_name='carla_server.Control.hand_brake', index=3,
number=4, type=8, cpp_type=7, label=1,
has_default_value=False, default_value=False,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='reverse', full_name='carla_server.Control.reverse', index=4,
number=5, type=8, cpp_type=7, label=1,
has_default_value=False, default_value=False,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
],
serialized_start=1086,
serialized_end=1180,
)
_MEASUREMENTS_PLAYERMEASUREMENTS = _descriptor.Descriptor(
name='PlayerMeasurements',
full_name='carla_server.Measurements.PlayerMeasurements',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='transform', full_name='carla_server.Measurements.PlayerMeasurements.transform', index=0,
number=1, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='acceleration', full_name='carla_server.Measurements.PlayerMeasurements.acceleration', index=1,
number=3, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='forward_speed', full_name='carla_server.Measurements.PlayerMeasurements.forward_speed', index=2,
number=4, type=2, cpp_type=6, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='collision_vehicles', full_name='carla_server.Measurements.PlayerMeasurements.collision_vehicles', index=3,
number=5, type=2, cpp_type=6, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='collision_pedestrians', full_name='carla_server.Measurements.PlayerMeasurements.collision_pedestrians', index=4,
number=6, type=2, cpp_type=6, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='collision_other', full_name='carla_server.Measurements.PlayerMeasurements.collision_other', index=5,
number=7, type=2, cpp_type=6, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='intersection_otherlane', full_name='carla_server.Measurements.PlayerMeasurements.intersection_otherlane', index=6,
number=8, type=2, cpp_type=6, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='intersection_offroad', full_name='carla_server.Measurements.PlayerMeasurements.intersection_offroad', index=7,
number=9, type=2, cpp_type=6, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='autopilot_control', full_name='carla_server.Measurements.PlayerMeasurements.autopilot_control', index=8,
number=10, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
],
serialized_start=1376,
serialized_end=1705,
)
_MEASUREMENTS = _descriptor.Descriptor(
name='Measurements',
full_name='carla_server.Measurements',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='platform_timestamp', full_name='carla_server.Measurements.platform_timestamp', index=0,
number=1, type=13, cpp_type=3, label=1,
has_default_value=False, default_value=0,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='game_timestamp', full_name='carla_server.Measurements.game_timestamp', index=1,
number=2, type=13, cpp_type=3, label=1,
has_default_value=False, default_value=0,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='player_measurements', full_name='carla_server.Measurements.player_measurements', index=2,
number=3, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
name='non_player_agents', full_name='carla_server.Measurements.non_player_agents', index=3,
number=4, type=11, cpp_type=10, label=3,
has_default_value=False, default_value=[],
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
],
extensions=[
],
nested_types=[_MEASUREMENTS_PLAYERMEASUREMENTS, ],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
],
serialized_start=1183,
serialized_end=1705,
)
_TRANSFORM.fields_by_name['location'].message_type = _VECTOR3D
_TRANSFORM.fields_by_name['orientation'].message_type = _VECTOR3D
_VEHICLE.fields_by_name['transform'].message_type = _TRANSFORM
_VEHICLE.fields_by_name['box_extent'].message_type = _VECTOR3D
_PEDESTRIAN.fields_by_name['transform'].message_type = _TRANSFORM
_PEDESTRIAN.fields_by_name['box_extent'].message_type = _VECTOR3D
_TRAFFICLIGHT.fields_by_name['transform'].message_type = _TRANSFORM
_TRAFFICLIGHT.fields_by_name['state'].enum_type = _TRAFFICLIGHT_STATE
_TRAFFICLIGHT_STATE.containing_type = _TRAFFICLIGHT
_SPEEDLIMITSIGN.fields_by_name['transform'].message_type = _TRANSFORM
_AGENT.fields_by_name['vehicle'].message_type = _VEHICLE
_AGENT.fields_by_name['pedestrian'].message_type = _PEDESTRIAN
_AGENT.fields_by_name['traffic_light'].message_type = _TRAFFICLIGHT
_AGENT.fields_by_name['speed_limit_sign'].message_type = _SPEEDLIMITSIGN
_AGENT.oneofs_by_name['agent'].fields.append(
_AGENT.fields_by_name['vehicle'])
_AGENT.fields_by_name['vehicle'].containing_oneof = _AGENT.oneofs_by_name['agent']
_AGENT.oneofs_by_name['agent'].fields.append(
_AGENT.fields_by_name['pedestrian'])
_AGENT.fields_by_name['pedestrian'].containing_oneof = _AGENT.oneofs_by_name['agent']
_AGENT.oneofs_by_name['agent'].fields.append(
_AGENT.fields_by_name['traffic_light'])
_AGENT.fields_by_name['traffic_light'].containing_oneof = _AGENT.oneofs_by_name['agent']
_AGENT.oneofs_by_name['agent'].fields.append(
_AGENT.fields_by_name['speed_limit_sign'])
_AGENT.fields_by_name['speed_limit_sign'].containing_oneof = _AGENT.oneofs_by_name['agent']
_SCENEDESCRIPTION.fields_by_name['player_start_spots'].message_type = _TRANSFORM
_MEASUREMENTS_PLAYERMEASUREMENTS.fields_by_name['transform'].message_type = _TRANSFORM
_MEASUREMENTS_PLAYERMEASUREMENTS.fields_by_name['acceleration'].message_type = _VECTOR3D
_MEASUREMENTS_PLAYERMEASUREMENTS.fields_by_name['autopilot_control'].message_type = _CONTROL
_MEASUREMENTS_PLAYERMEASUREMENTS.containing_type = _MEASUREMENTS
_MEASUREMENTS.fields_by_name['player_measurements'].message_type = _MEASUREMENTS_PLAYERMEASUREMENTS
_MEASUREMENTS.fields_by_name['non_player_agents'].message_type = _AGENT
DESCRIPTOR.message_types_by_name['Vector3D'] = _VECTOR3D
DESCRIPTOR.message_types_by_name['Transform'] = _TRANSFORM
DESCRIPTOR.message_types_by_name['Vehicle'] = _VEHICLE
DESCRIPTOR.message_types_by_name['Pedestrian'] = _PEDESTRIAN
DESCRIPTOR.message_types_by_name['TrafficLight'] = _TRAFFICLIGHT
DESCRIPTOR.message_types_by_name['SpeedLimitSign'] = _SPEEDLIMITSIGN
DESCRIPTOR.message_types_by_name['Agent'] = _AGENT
DESCRIPTOR.message_types_by_name['RequestNewEpisode'] = _REQUESTNEWEPISODE
DESCRIPTOR.message_types_by_name['SceneDescription'] = _SCENEDESCRIPTION
DESCRIPTOR.message_types_by_name['EpisodeStart'] = _EPISODESTART
DESCRIPTOR.message_types_by_name['EpisodeReady'] = _EPISODEREADY
DESCRIPTOR.message_types_by_name['Control'] = _CONTROL
DESCRIPTOR.message_types_by_name['Measurements'] = _MEASUREMENTS
_sym_db.RegisterFileDescriptor(DESCRIPTOR)
Vector3D = _reflection.GeneratedProtocolMessageType('Vector3D', (_message.Message,), dict(
DESCRIPTOR = _VECTOR3D,
__module__ = 'carla_server_pb2'
# @@protoc_insertion_point(class_scope:carla_server.Vector3D)
))
_sym_db.RegisterMessage(Vector3D)
Transform = _reflection.GeneratedProtocolMessageType('Transform', (_message.Message,), dict(
DESCRIPTOR = _TRANSFORM,
__module__ = 'carla_server_pb2'
# @@protoc_insertion_point(class_scope:carla_server.Transform)
))
_sym_db.RegisterMessage(Transform)
Vehicle = _reflection.GeneratedProtocolMessageType('Vehicle', (_message.Message,), dict(
DESCRIPTOR = _VEHICLE,
__module__ = 'carla_server_pb2'
# @@protoc_insertion_point(class_scope:carla_server.Vehicle)
))
_sym_db.RegisterMessage(Vehicle)
Pedestrian = _reflection.GeneratedProtocolMessageType('Pedestrian', (_message.Message,), dict(
DESCRIPTOR = _PEDESTRIAN,
__module__ = 'carla_server_pb2'
# @@protoc_insertion_point(class_scope:carla_server.Pedestrian)
))
_sym_db.RegisterMessage(Pedestrian)
TrafficLight = _reflection.GeneratedProtocolMessageType('TrafficLight', (_message.Message,), dict(
DESCRIPTOR = _TRAFFICLIGHT,
__module__ = 'carla_server_pb2'
# @@protoc_insertion_point(class_scope:carla_server.TrafficLight)
))
_sym_db.RegisterMessage(TrafficLight)
SpeedLimitSign = _reflection.GeneratedProtocolMessageType('SpeedLimitSign', (_message.Message,), dict(
DESCRIPTOR = _SPEEDLIMITSIGN,
__module__ = 'carla_server_pb2'
# @@protoc_insertion_point(class_scope:carla_server.SpeedLimitSign)
))
_sym_db.RegisterMessage(SpeedLimitSign)
Agent = _reflection.GeneratedProtocolMessageType('Agent', (_message.Message,), dict(
DESCRIPTOR = _AGENT,
__module__ = 'carla_server_pb2'
# @@protoc_insertion_point(class_scope:carla_server.Agent)
))
_sym_db.RegisterMessage(Agent)
RequestNewEpisode = _reflection.GeneratedProtocolMessageType('RequestNewEpisode', (_message.Message,), dict(
DESCRIPTOR = _REQUESTNEWEPISODE,
__module__ = 'carla_server_pb2'
# @@protoc_insertion_point(class_scope:carla_server.RequestNewEpisode)
))
_sym_db.RegisterMessage(RequestNewEpisode)
SceneDescription = _reflection.GeneratedProtocolMessageType('SceneDescription', (_message.Message,), dict(
DESCRIPTOR = _SCENEDESCRIPTION,
__module__ = 'carla_server_pb2'
# @@protoc_insertion_point(class_scope:carla_server.SceneDescription)
))
_sym_db.RegisterMessage(SceneDescription)
EpisodeStart = _reflection.GeneratedProtocolMessageType('EpisodeStart', (_message.Message,), dict(
DESCRIPTOR = _EPISODESTART,
__module__ = 'carla_server_pb2'
# @@protoc_insertion_point(class_scope:carla_server.EpisodeStart)
))
_sym_db.RegisterMessage(EpisodeStart)
EpisodeReady = _reflection.GeneratedProtocolMessageType('EpisodeReady', (_message.Message,), dict(
DESCRIPTOR = _EPISODEREADY,
__module__ = 'carla_server_pb2'
# @@protoc_insertion_point(class_scope:carla_server.EpisodeReady)
))
_sym_db.RegisterMessage(EpisodeReady)
Control = _reflection.GeneratedProtocolMessageType('Control', (_message.Message,), dict(
DESCRIPTOR = _CONTROL,
__module__ = 'carla_server_pb2'
# @@protoc_insertion_point(class_scope:carla_server.Control)
))
_sym_db.RegisterMessage(Control)
Measurements = _reflection.GeneratedProtocolMessageType('Measurements', (_message.Message,), dict(
PlayerMeasurements = _reflection.GeneratedProtocolMessageType('PlayerMeasurements', (_message.Message,), dict(
DESCRIPTOR = _MEASUREMENTS_PLAYERMEASUREMENTS,
__module__ = 'carla_server_pb2'
# @@protoc_insertion_point(class_scope:carla_server.Measurements.PlayerMeasurements)
))
,
DESCRIPTOR = _MEASUREMENTS,
__module__ = 'carla_server_pb2'
# @@protoc_insertion_point(class_scope:carla_server.Measurements)
))
_sym_db.RegisterMessage(Measurements)
_sym_db.RegisterMessage(Measurements.PlayerMeasurements)
DESCRIPTOR.has_options = True
DESCRIPTOR._options = _descriptor._ParseOptions(descriptor_pb2.FileOptions(), _b('\370\001\001'))
# @@protoc_insertion_point(module_scope)

View File

@ -0,0 +1,190 @@
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
# Barcelona (UAB), and the INTEL Visual Computing Lab.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
"""CARLA Client."""
import struct
from contextlib import contextmanager
from . import sensor
from . import settings
from . import tcp
from . import util
try:
from . import carla_server_pb2 as carla_protocol
except ImportError:
raise RuntimeError('cannot import "carla_server_pb2.py", run the protobuf compiler to generate this file')
VehicleControl = carla_protocol.Control
@contextmanager
def make_carla_client(host, world_port, timeout=15):
"""Context manager for creating and connecting a CarlaClient."""
with util.make_connection(CarlaClient, host, world_port, timeout) as client:
yield client
class CarlaClient(object):
"""The CARLA client. Manages communications with the CARLA server."""
def __init__(self, host, world_port, timeout=15):
self._world_client = tcp.TCPClient(host, world_port, timeout)
self._stream_client = tcp.TCPClient(host, world_port + 1, timeout)
self._control_client = tcp.TCPClient(host, world_port + 2, timeout)
self._current_settings = None
self._is_episode_requested = False
self._sensor_names = []
def connect(self, connection_attempts=10):
"""
Try to establish a connection to a CARLA server at the given host:port.
"""
self._world_client.connect(connection_attempts)
def disconnect(self):
"""Disconnect from server."""
self._control_client.disconnect()
self._stream_client.disconnect()
self._world_client.disconnect()
def connected(self):
"""Return whether there is an active connection."""
return self._world_client.connected()
def load_settings(self, carla_settings):
"""
Load new settings and request a new episode based on these settings.
carla_settings object must be convertible to a str holding the contents
of a CarlaSettings.ini file.
Return a protobuf object holding the scene description.
"""
self._current_settings = carla_settings
return self._request_new_episode(carla_settings)
def start_episode(self, player_start_index):
"""
Start the new episode at the player start given by the
player_start_index. The list of player starts is retrieved by
"load_settings".
The new episode is started based on the last settings loaded by
"load_settings".
This function waits until the server answers with an EpisodeReady.
"""
if self._current_settings is None:
raise RuntimeError('no settings loaded, cannot start episode')
# if no new settings are loaded, request new episode with previous
if not self._is_episode_requested:
self._request_new_episode(self._current_settings)
try:
pb_message = carla_protocol.EpisodeStart()
pb_message.player_start_spot_index = player_start_index
self._world_client.write(pb_message.SerializeToString())
# Wait for EpisodeReady.
data = self._world_client.read()
if not data:
raise RuntimeError('failed to read data from server')
pb_message = carla_protocol.EpisodeReady()
pb_message.ParseFromString(data)
if not pb_message.ready:
raise RuntimeError('cannot start episode: server failed to start episode')
# We can start the agent clients now.
self._stream_client.connect()
self._control_client.connect()
# Set again the status for no episode requested
finally:
self._is_episode_requested = False
def read_data(self):
"""
Read the data sent from the server this frame. The episode must be
started. Return a pair containing the protobuf object containing the
measurements followed by the raw data of the sensors.
"""
# Read measurements.
data = self._stream_client.read()
if not data:
raise RuntimeError('failed to read data from server')
pb_message = carla_protocol.Measurements()
pb_message.ParseFromString(data)
# Read sensor data.
raw_sensor_data = self._stream_client.read()
return pb_message, self._parse_raw_sensor_data(raw_sensor_data)
def send_control(self, *args, **kwargs):
"""
Send the VehicleControl to be applied this frame.
If synchronous mode was requested, the server will pause the simulation
until this message is received.
"""
if isinstance(args[0] if args else None, carla_protocol.Control):
pb_message = args[0]
else:
pb_message = carla_protocol.Control()
pb_message.steer = kwargs.get('steer', 0.0)
pb_message.throttle = kwargs.get('throttle', 0.0)
pb_message.brake = kwargs.get('brake', 0.0)
pb_message.hand_brake = kwargs.get('hand_brake', False)
pb_message.reverse = kwargs.get('reverse', False)
self._control_client.write(pb_message.SerializeToString())
def _request_new_episode(self, carla_settings):
"""
Internal function to request a new episode. Prepare the client for a new
episode by disconnecting agent clients.
"""
# Disconnect agent clients.
self._stream_client.disconnect()
self._control_client.disconnect()
# Send new episode request.
pb_message = carla_protocol.RequestNewEpisode()
pb_message.ini_file = str(carla_settings)
self._world_client.write(pb_message.SerializeToString())
# Read scene description.
data = self._world_client.read()
if not data:
raise RuntimeError('failed to read data from server')
pb_message = carla_protocol.SceneDescription()
pb_message.ParseFromString(data)
if len(pb_message.player_start_spots) < 1:
raise RuntimeError("received 0 player start spots")
self._sensor_names = settings._get_sensor_names(carla_settings)
self._is_episode_requested = True
return pb_message
def _parse_raw_sensor_data(self, raw_data):
"""Return a dict of {'sensor_name': sensor_data, ...}."""
return dict((name, data) for name, data in zip(
self._sensor_names,
self._iterate_sensor_data(raw_data)))
@staticmethod
def _iterate_sensor_data(raw_data):
# At this point the only sensors available are images, the raw_data
# consists of images only.
image_types = ['None', 'SceneFinal', 'Depth', 'SemanticSegmentation']
gettype = lambda id: image_types[id] if len(image_types) > id else 'Unknown'
getval = lambda index: struct.unpack('<L', raw_data[index*4:index*4+4])[0]
total_size = len(raw_data) / 4
index = 0
while index < total_size:
width = getval(index)
height = getval(index + 1)
image_type = gettype(getval(index + 2))
begin = index + 3
end = begin + width * height
index = end
yield sensor.Image(width, height, image_type, raw_data[begin*4:end*4])

View File

@ -1,221 +0,0 @@
#!/usr/bin/env python3
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
# Barcelona (UAB), and the INTEL Visual Computing Lab.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
"""Basic CARLA client example."""
import sys
is_py2 = sys.version[0] == '2'
if is_py2:
import Queue as Queue
else:
import queue as Queue
from threading import Thread
import time
import random
from PIL import Image
from .socket_util import *
import io
import sys
import numpy as np
import logging
from .protoc import *
def threaded(fn):
def wrapper(*args, **kwargs):
thread = Thread(target=fn, args=args, kwargs=kwargs)
thread.setDaemon(True)
thread.start()
return thread
return wrapper
class DataStream(object):
def __init__(self,image_x=640,image_y=480):
self._data_buffer = Queue.Queue(1)
self._image_x = image_x
self._image_y = image_y
self._socket = 0
self._running = True
def _read_image(self,imagedata,pointer):
width = struct.unpack('<L',imagedata[pointer:(pointer+4)])[0]
pointer +=4
height = struct.unpack('<L',imagedata[pointer:(pointer+4)])[0]
pointer +=4
im_type = struct.unpack('<L',imagedata[pointer:(pointer+4)])[0]
pointer +=4
image_size = width*height*4
image_bytes = imagedata[pointer:(pointer+image_size)]
dt = np.dtype("uint8")
new_image =np.frombuffer(image_bytes,dtype=dt)
new_image = np.reshape(new_image,(self._image_y,self._image_x,4)) # TODO: make this generic
pointer += image_size
return new_image,im_type,pointer
def receive_data(self):
depths = []
# First we get the message of the google protocol
capture_time = time.time()
try:
data = get_message(self._socket)
except Exception:
if self._running:
logging.exception("Error on Datastream, Raise Again")
raise Exception
return [] # return something empty, since it is not running anymore
measurements = Measurements()
measurements.ParseFromString(data)
player_measures = measurements.player_measurements
non_player_agents = measurements.non_player_agents
try:
logging.debug(" Trying to get the image")
imagedata = get_message(self._socket)
except Exception:
if self._running:
logging.exception("Error on Datastream, Raise Again")
raise Exception
return [] # return something empty, since it is not running anymore
meas_dict ={}
meas_dict.update({'RAW_BGRA':[]})
meas_dict.update({'BGRA':[]})
meas_dict.update({'Depth':[]})
meas_dict.update({'Labels':[]})
pointer = 0
while pointer < len(imagedata):
image,im_type,pointer = self._read_image(imagedata,pointer)
if im_type == 0:
meas_dict['RAW_BGRA'].append(image)
logging.debug("RECEIVED rgb_raw")
if im_type == 1:
meas_dict['BGRA'].append(image)
logging.debug("RECEIVED rgb")
if im_type == 2:
meas_dict['Depth'].append(image)
logging.debug("RECEIVED depht")
if im_type == 3:
meas_dict['Labels'].append(image)
logging.debug("RECEIVED scene_seg")
meas_dict.update({'WallTime':measurements.platform_timestamp})
meas_dict.update({'GameTime':measurements.game_timestamp})
meas_dict.update({'PlayerMeasurements':player_measures})
meas_dict.update({'Agents':non_player_agents})
return meas_dict
def get_the_latest_data(self):
try:
data = self._data_buffer.get(timeout=20)
except Queue.Empty:
logging.exception("ERROR: No Data in 20 seconds, disconecting and reconecting from server ")
self._running = False
raise Queue.Empty
except Exception:
logging.exception("Other error on getting queue")
raise Exception
else:
self._data_buffer.task_done()
return data
def start(self,socket):
self._socket = socket
self.run()
def stop(self):
self._running = False
disconnect(self._socket)
self.clean()
# We clean the buffer so that no old data is going to be used
def clean(self):
while True:
try:
aux=self._data_buffer.get(False)
except Queue.Empty:
return
@threaded
def run(self):
try:
while self._running:
try:
self._data_buffer.put(self.receive_data(),timeout=20)
except Queue.Full:
logging.exception("ERROR: Queue Full for more than 20 seconds...")
except Exception as e:
logging.exception("Some internal Socket error ")
self._running = False
except RuntimeError:
logging.exception("Unexpected RuntimeError")
self._running = False
finally:
logging.debug("We Are finishing the datastream thread ")

View File

@ -0,0 +1,103 @@
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
# Barcelona (UAB), and the INTEL Visual Computing Lab.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
"""
Handy conversions for CARLA images.
The functions here are provided for real-time display, if you want to save the
converted images, save the images from Python without conversion and convert
them afterwards with the C++ implementation at "Util/ImageConverter" as it
provides considerably better performance.
"""
try:
import numpy
except ImportError:
raise RuntimeError('cannot import numpy, make sure numpy package is installed')
from . import sensor
def to_bgra_array(image):
"""Convert a CARLA raw image to a BGRA numpy array."""
if not isinstance(image, sensor.Image):
raise ValueError("Argument must be a carla.sensor.Image")
array = numpy.frombuffer(image.raw_data, dtype=numpy.dtype("uint8"))
array = numpy.reshape(array, (image.height, image.width, 4))
return array
def to_rgb_array(image):
"""Convert a CARLA raw image to a RGB numpy array."""
array = to_bgra_array(image)
# Convert BGRA to RGB.
array = array[:, :, :3]
array = array[:, :, ::-1]
return array
def labels_to_array(image):
"""
Convert an image containing CARLA semantic segmentation labels to a 2D array
containing the label of each pixel.
"""
return to_bgra_array(image)[:, :, 2]
def labels_to_cityscapes_palette(image):
"""
Convert an image containing CARLA semantic segmentation labels to
Cityscapes palette.
"""
classes = {
0: [0, 0, 0], # None
1: [70, 70, 70], # Buildings
2: [190, 153, 153], # Fences
3: [72, 0, 90], # Other
4: [220, 20, 60], # Pedestrians
5: [153, 153, 153], # Poles
6: [157, 234, 50], # RoadLines
7: [128, 64, 128], # Roads
8: [244, 35, 232], # Sidewalks
9: [107, 142, 35], # Vegetation
10: [0, 0, 255], # Vehicles
11: [102, 102, 156], # Walls
12: [220, 220, 0] # TrafficSigns
}
array = labels_to_array(image)
result = numpy.zeros((array.shape[0], array.shape[1], 3))
for key, value in classes.items():
result[numpy.where(array == key)] = value
return result
def depth_to_array(image):
"""
Convert an image containing CARLA encoded depth-map to a 2D array containing
the depth value of each pixel normalized between [0.0, 1.0].
"""
array = to_bgra_array(image)
array = array.astype(numpy.float32)
# Apply (R + G * 256 + B * 256 * 256) / (256 * 256 * 256 - 1).
grayscale = numpy.dot(array[:, :, :3], [256.0 * 256.0, 256.0, 1.0])
grayscale /= (256.0 * 256.0 * 256.0 - 1.0)
return grayscale
def depth_to_logarithmic_grayscale(image):
"""
Convert an image containing CARLA encoded depth-map to a logarithmic
grayscale image array.
"""
grayscale = depth_to_array(image)
# Convert to logarithmic depth.
logdepth = numpy.ones(grayscale.shape) + (numpy.log(grayscale) / 5.70378)
logdepth = numpy.clip(logdepth, 0.0, 1.0)
logdepth *= 255.0
# Expand to three colors.
return numpy.repeat(logdepth[:, :, numpy.newaxis], 3, axis=2)

Binary file not shown.

After

Width:  |  Height:  |  Size: 33 KiB

View File

@ -0,0 +1,49 @@
0.0,0.0,-3811.000000
0.000000,0.000000,0.0
1.000000,1.000000,1.000000
-1643.022,-1643.022,0.000
49, 41
0,0 0,40 40
0,40 0,0 40
48,40 41,40 7
41,40 48,40 7
48,0 48,40 40
48,40 48,0 40
0,0 11,0 11
11,0 0,0 11
41,0 48,0 7
48,0 41,0 7
41,40 11,40 30
11,40 41,40 30
41,0 41,7 7
41,7 41,0 7
11,40 0,40 11
0,40 11,40 11
11,0 19,0 8
19,0 11,0 8
11,40 11,24 16
11,24 11,40 16
41,24 41,40 16
41,40 41,24 16
11,24 11,16 8
11,16 11,24 8
41,24 11,24 30
11,24 41,24 30
41,16 41,24 8
41,24 41,16 8
11,16 11,7 9
11,7 11,16 9
41,16 11,16 30
11,16 41,16 30
41,7 41,16 9
41,16 41,7 9
11,7 11,0 7
11,0 11,7 7
41,7 19,7 22
19,7 41,7 22
19,0 41,0 22
41,0 19,0 22
19,7 11,7 8
11,7 19,7 8
19,0 19,7 7
19,7 19,0 7

Binary file not shown.

After

Width:  |  Height:  |  Size: 15 KiB

View File

@ -0,0 +1,37 @@
544.000000,-10748.000000,-22.000000
0.000000,0.000000,0.000000
1.000000,1.000000,1.000000
-1643.022,-1643.022,0.000
25, 25
0,10 0,24 14
0,24 0,10 14
24,24 6,24 18
6,24 24,24 18
24,0 24,10 10
24,10 24,0 10
0,0 24,0 24
24,0 0,0 24
0,10 0,0 10
0,0 0,10 10
24,10 24,16 6
24,16 24,10 6
0,10 6,10 6
6,10 0,10 6
6,24 0,24 6
0,24 6,24 6
6,10 17,10 11
17,10 6,10 11
6,24 6,16 8
6,16 6,24 8
24,16 24,24 8
24,24 24,16 8
6,16 6,10 6
6,10 6,16 6
24,16 17,16 7
17,16 24,16 7
17,16 6,16 11
6,16 17,16 11
17,10 24,10 7
24,10 17,10 7
17,16 17,10 6
17,10 17,16 6

View File

@ -0,0 +1,140 @@
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
# Barcelona (UAB), and the INTEL Visual Computing Lab.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
"""Class used for operating the city map."""
import math
import os
try:
import numpy as np
except ImportError:
raise RuntimeError('cannot import numpy, make sure numpy package is installed')
try:
from PIL import Image
except ImportError:
raise RuntimeError('cannot import PIL, make sure pillow package is installed')
def string_to_node(string):
vec = string.split(',')
return (int(vec[0]), int(vec[1]))
def string_to_floats(string):
vec = string.split(',')
return (float(vec[0]), float(vec[1]), float(vec[2]))
class CarlaMap(object):
def __init__(self, city):
dir_path = os.path.dirname(__file__)
city_file = os.path.join(dir_path, city + '.txt')
city_map_file = os.path.join(dir_path, city + '.png')
with open(city_file, 'r') as file:
linewordloffset = file.readline()
# The offset of the world from the zero coordinates ( The
# coordinate we consider zero)
self.worldoffset = string_to_floats(linewordloffset)
lineworldangles = file.readline()
self.angles = string_to_floats(lineworldangles)
self.worldrotation = np.array([
[math.cos(math.radians(self.angles[2])), -math.sin(math.radians(self.angles[2])), 0.0],
[math.sin(math.radians(self.angles[2])), math.cos(math.radians(self.angles[2])), 0.0],
[0.0, 0.0, 1.0]])
# Ignore for now, these are offsets for map coordinates and scale
# (not used).
_ = file.readline()
linemapoffset = file.readline()
# The offset of the map zero coordinate.
self.mapoffset = string_to_floats(linemapoffset)
# the graph resolution.
linegraphres = file.readline()
self.resolution = string_to_node(linegraphres)
# The number of game units per pixel.
self.pixel_density = 16.43
self.map_image = Image.open(city_map_file)
self.map_image.load()
self.map_image = np.asarray(self.map_image, dtype="int32")
def draw_position_on_map(self, position, color, size=20):
position = self.get_position_on_map([position.x, position.y, position.z])
for i in range(0, size):
self.map_image[int(position[1]), int(position[0])] = color
self.map_image[int(position[1]) + i, int(position[0])] = color
self.map_image[int(position[1]), int(position[0]) + i] = color
self.map_image[int(position[1]) - i, int(position[0])] = color
self.map_image[int(position[1]), int(position[0]) - i] = color
self.map_image[int(position[1]) + i, int(position[0]) + i] = color
self.map_image[int(position[1]) - i, int(position[0]) - i] = color
self.map_image[int(position[1]) + i, int(position[0]) - i] = color
self.map_image[int(position[1]) - i, int(position[0]) + i] = color
def get_map(self, size=None):
if size is not None:
img = Image.fromarray(self.map_image.astype(np.uint8))
img = img.resize((size[1], size[0]), Image.ANTIALIAS)
img.load()
return np.fliplr(np.asarray(img, dtype="int32"))
return np.fliplr(self.map_image)
def get_position_on_map(self, world):
"""Get the position on the map for a certain world position."""
relative_location = []
pixel = []
rotation = np.array([world[0], world[1], world[2]])
rotation = rotation.dot(self.worldrotation)
relative_location.append(rotation[0] + self.worldoffset[0] - self.mapoffset[0])
relative_location.append(rotation[1] + self.worldoffset[1] - self.mapoffset[1])
relative_location.append(rotation[2] + self.worldoffset[2] - self.mapoffset[2])
pixel.append(math.floor(relative_location[0] / float(self.pixel_density)))
pixel.append(math.floor(relative_location[1] / float(self.pixel_density)))
return pixel
def get_position_on_world(self, pixel):
"""Get world position of a certain map position."""
relative_location = []
world_vertex = []
relative_location.append(pixel[0] * self.pixel_density)
relative_location.append(pixel[1] * self.pixel_density)
world_vertex.append(relative_location[0] + self.mapoffset[0] - self.worldoffset[0])
world_vertex.append(relative_location[1] + self.mapoffset[1] - self.worldoffset[1])
world_vertex.append(22) # Z does not matter for now.
return world_vertex
def get_lane_orientation(self, world):
"""Get the lane orientation of a certain world position."""
relative_location = []
pixel = []
rotation = np.array([world[0], world[1], world[2]])
rotation = rotation.dot(self.worldrotation)
relative_location.append(rotation[0] + self.worldoffset[0] - self.mapoffset[0])
relative_location.append(rotation[1] + self.worldoffset[1] - self.mapoffset[1])
relative_location.append(rotation[2] + self.worldoffset[2] - self.mapoffset[2])
pixel.append(math.floor(relative_location[0] / float(self.pixel_density)))
pixel.append(math.floor(relative_location[1] / float(self.pixel_density)))
ori = self.map_image[int(pixel[1]), int(pixel[0]), 2]
ori = ((float(ori) / 255.0)) * 2 * math.pi
return (-math.cos(ori), -math.sin(ori))

View File

@ -1,2 +0,0 @@
from .carla_server_pb2 import SceneDescription,EpisodeStart,EpisodeReady,Control,Measurements,RequestNewEpisode

View File

@ -0,0 +1,122 @@
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
# Barcelona (UAB), and the INTEL Visual Computing Lab.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
"""CARLA sensors."""
import os
# ==============================================================================
# -- Sensor --------------------------------------------------------------------
# ==============================================================================
class Sensor(object):
"""
Base class for sensor descriptions. Used to add sensors to CarlaSettings.
"""
pass
class Camera(Sensor):
"""
Camera description. This class can be added to a CarlaSettings object to add
a camera to the player vehicle.
"""
def __init__(self, name, **kwargs):
self.CameraName = name
self.PostProcessing = 'SceneFinal'
self.ImageSizeX = 800
self.ImageSizeY = 600
self.CameraFOV = 90
self.CameraPositionX = 140
self.CameraPositionY = 0
self.CameraPositionZ = 140
self.CameraRotationPitch = 0
self.CameraRotationRoll = 0
self.CameraRotationYaw = 0
self.set(**kwargs)
def set(self, **kwargs):
for key, value in kwargs.items():
if not hasattr(self, key):
raise ValueError('CarlaSettings.Camera: no key named %r' % key)
setattr(self, key, value)
def set_image_size(self, pixels_x, pixels_y):
self.ImageSizeX = pixels_x
self.ImageSizeY = pixels_y
def set_position(self, x, y, z):
self.CameraPositionX = x
self.CameraPositionY = y
self.CameraPositionZ = z
def set_rotation(self, pitch, roll, yaw):
self.CameraRotationPitch = pitch
self.CameraRotationRoll = roll
self.CameraRotationYaw = yaw
# ==============================================================================
# -- SensorData ----------------------------------------------------------------
# ==============================================================================
class SensorData(object):
"""Base class for sensor data returned from the server."""
pass
class Image(SensorData):
"""Data generated by a Camera."""
def __init__(self, width, height, image_type, raw_data):
assert len(raw_data) == 4 * width * height
self.width = width
self.height = height
self.type = image_type
self.raw_data = raw_data
self._converted_data = None
@property
def data(self):
"""
Lazy initialization for data property, stores converted data in its
default format.
"""
if self._converted_data is None:
from . import image_converter
if self.type == 'Depth':
self._converted_data = image_converter.depth_to_array(self)
elif self.type == 'SemanticSegmentation':
self._converted_data = image_converter.labels_to_array(self)
else:
self._converted_data = image_converter.to_rgb_array(self)
return self._converted_data
def save_to_disk(self, filename):
"""Save this image to disk (requires PIL installed)."""
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=(self.width, self.height),
data=self.raw_data,
decoder_name='raw')
b, g, r, a = image.split()
image = PImage.merge("RGB", (r, g, b))
folder = os.path.dirname(filename)
if not os.path.isdir(folder):
os.makedirs(folder)
image.save(filename)

View File

@ -6,53 +6,32 @@
"""CARLA Settings""" """CARLA Settings"""
import configparser
import io import io
import random import random
import sys
if sys.version_info >= (3, 0):
from configparser import ConfigParser
else:
from ConfigParser import RawConfigParser as ConfigParser
from . import sensor as carla_sensor
MAX_NUMBER_OF_WEATHER_IDS = 14 MAX_NUMBER_OF_WEATHER_IDS = 14
class Camera(object):
"""Camera description. To be added to CarlaSettings."""
def __init__(self, name, **kwargs):
self.CameraName = name
self.PostProcessing = 'SceneFinal'
self.ImageSizeX = 800
self.ImageSizeY = 600
self.CameraFOV = 90
self.CameraPositionX = 15
self.CameraPositionY = 0
self.CameraPositionZ = 123
self.CameraRotationPitch = 8
self.CameraRotationRoll = 0
self.CameraRotationYaw = 0
self.set(**kwargs)
def set(self, **kwargs):
for key, value in kwargs.items():
if not hasattr(self, key):
raise ValueError('CarlaSettings.Camera: no key named %r' % key)
setattr(self, key, value)
def set_image_size(self, pixels_x, pixels_y):
self.ImageSizeX = pixels_x
self.ImageSizeY = pixels_y
def set_position(self, x, y, z):
self.CameraPositionX = x
self.CameraPositionY = y
self.CameraPositionZ = z
def set_rotation(self, pitch, roll, yaw):
self.CameraRotationPitch = pitch
self.CameraRotationRoll = roll
self.CameraRotationYaw = yaw
class CarlaSettings(object): class CarlaSettings(object):
"""CARLA settings object. Convertible to str as CarlaSettings.ini.""" """
The CarlaSettings object controls the settings of an episode. The __str__
method retrieves an str with a CarlaSettings.ini file contents.
"""
def __init__(self, **kwargs): def __init__(self, **kwargs):
# [CARLA/Server] # [CARLA/Server]
self.SynchronousMode = True self.SynchronousMode = True
@ -74,25 +53,28 @@ class CarlaSettings(object):
raise ValueError('CarlaSettings: no key named %r' % key) raise ValueError('CarlaSettings: no key named %r' % key)
setattr(self, key, value) setattr(self, key, value)
def get_number_of_agents(self):
if not self.SendNonPlayerAgentsInfo:
return 0
return self.NumberOfVehicles + self.NumberOfPedestrians
def randomize_seeds(self): def randomize_seeds(self):
"""
Randomize the seeds of the new episode's pseudo-random number
generators.
"""
self.SeedVehicles = random.getrandbits(16) self.SeedVehicles = random.getrandbits(16)
self.SeedPedestrians = random.getrandbits(16) self.SeedPedestrians = random.getrandbits(16)
def randomize_weather(self): def randomize_weather(self):
"""Randomized the WeatherId."""
self.WeatherId = random.randint(0, MAX_NUMBER_OF_WEATHER_IDS) self.WeatherId = random.randint(0, MAX_NUMBER_OF_WEATHER_IDS)
def add_camera(self, camera): def add_sensor(self, sensor):
if not isinstance(camera, Camera): """Add a sensor to the player vehicle (see sensor.py)."""
raise ValueError('Can only add instances of carla_settings.Camera') if isinstance(sensor, carla_sensor.Camera):
self._cameras.append(camera) self._cameras.append(sensor)
else:
raise ValueError('Sensor not supported')
def __str__(self): def __str__(self):
ini = configparser.ConfigParser() """Converts this object to an INI formatted string."""
ini = ConfigParser()
ini.optionxform=str ini.optionxform=str
S_SERVER = 'CARLA/Server' S_SERVER = 'CARLA/Server'
S_LEVEL = 'CARLA/LevelSettings' S_LEVEL = 'CARLA/LevelSettings'
@ -131,6 +113,32 @@ class CarlaSettings(object):
'CameraRotationRoll', 'CameraRotationRoll',
'CameraRotationYaw']) 'CameraRotationYaw'])
text = io.StringIO() if sys.version_info >= (3, 0):
text = io.StringIO()
else:
text = io.BytesIO()
ini.write(text) ini.write(text)
return text.getvalue().replace(' = ', '=') return text.getvalue().replace(' = ', '=')
def _get_sensor_names(settings):
"""
Return a list with the names of the sensors defined in the settings object.
The settings object can be a CarlaSettings or an INI formatted string.
"""
if isinstance(settings, CarlaSettings):
return [camera.CameraName for camera in settings._cameras]
ini = ConfigParser()
if sys.version_info >= (3, 0):
ini.readfp(io.StringIO(settings))
else:
ini.readfp(io.BytesIO(settings))
section_name = 'CARLA/SceneCapture'
option_name = 'Cameras'
if ini.has_section(section_name) and ini.has_option(section_name, option_name):
cameras = ini.get(section_name, option_name)
return cameras.split(',')
return []

View File

@ -1,114 +0,0 @@
#!/usr/bin/env python3
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
# Barcelona (UAB), and the INTEL Visual Computing Lab.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
import binascii
import socket
import struct
import logging
import time
import select
def int2bytes(i):
hex_string = '%x' % i
n = len(hex_string)
return binascii.unhexlify(hex_string.zfill(n + (n & 1)))
def bytes2int(str):
return int(str.encode('hex'), 16)
def connect(host,port):
try:
sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
sock.settimeout(100)
except socket.error:
logginge.exception("Error Creating Socket World")
sock.connect((host,port))
logging.debug("connected to %s port %d" %(host,port))
return sock
def pers_connect(host,port):
for attempt in range(10):
try:
sock = connect(host,port)
return sock
except Exception as e:
logging.exception("Failure on connection")
time.sleep(1)
continue
else:
break
raise socket.error
def disconnect(sock):
sock.shutdown(socket.SHUT_RDWR)
sock.close()
def send_message(sock, message):
""" Send a serialized message (protobuf Message interface)
to a socket, prepended by its length packed in 4
bytes (big endian).
"""
s = message.SerializeToString()
packed_len =struct.pack('<L', len(s)) #int2bytes(len(s))
logging.debug( "SOCKET Send: %d bytes" % int(len(s)))
sock.sendall(packed_len + s)
def get_message(sock):
""" Read a message from a socket.
"""
len_buf = socket_read_n(sock, 4)
msg_len = struct.unpack('<L', len_buf)[0]
logging.debug( "SOCKET RECEIVED: %d bytes" % msg_len)
msg_buf = socket_read_n(sock, msg_len)
return msg_buf
def socket_read_n(sock,n):
""" Read exactly n bytes from the socket.
Raise RuntimeError if the connection closed before
n bytes were read.
"""
buf = b''
while n > 0:
sock.setblocking(0)
ready = select.select([sock], [], [], 3)
if ready[0]:
try:
data = sock.recv(n)
if data == b'':
raise RuntimeError('unexpected connection close')
buf += data
n -= len(data)
except socket.error:
raise socket.error
sock.setblocking(1)
return buf

98
PythonClient/carla/tcp.py Normal file
View File

@ -0,0 +1,98 @@
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
# Barcelona (UAB), and the INTEL Visual Computing Lab.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
"""Basic TCP client."""
import logging
import socket
import struct
import time
class TCPConnectionError(Exception):
pass
class TCPClient(object):
"""
Basic networking client for TCP connections. Errors occurred during
networking operations are raised as TCPConnectionError.
Received messages are expected to be prepended by a int32 defining the
message size. Messages are sent following this convention.
"""
def __init__(self, host, port, timeout):
self._host = host
self._port = port
self._timeout = timeout
self._socket = None
self._logprefix = '(%s:%s) ' % (self._host, self._port)
def connect(self, connection_attempts=10):
"""Try to establish a connection to the given host:port."""
connection_attempts = max(1, connection_attempts)
error = None
for attempt in range(1, connection_attempts + 1):
try:
self._socket = socket.create_connection(address=(self._host, self._port), timeout=self._timeout)
self._socket.settimeout(self._timeout)
logging.debug(self._logprefix + 'connected')
return
except Exception as exception:
error = exception
logging.debug(self._logprefix + 'connection attempt %d: %s', attempt, error)
time.sleep(1)
continue
self._reraise_exception_as_tcp_error('failed to connect', error)
def disconnect(self):
"""Disconnect any active connection."""
if self._socket is not None:
logging.debug(self._logprefix + 'disconnecting')
self._socket.close()
self._socket = None
def connected(self):
"""Return whether there is an active connection."""
return self._socket is not None
def write(self, message):
"""Send message to the server."""
if self._socket is None:
raise TCPConnectionError(self._logprefix + 'not connected')
header = struct.pack('<L', len(message))
try:
self._socket.sendall(header + message)
except Exception as exception:
self._reraise_exception_as_tcp_error('failed to write data', exception)
def read(self):
"""Read a message from the server."""
header = self._read_n(4)
if not header:
raise TCPConnectionError(self._logprefix + 'connection closed')
length = struct.unpack('<L', header)[0]
data = self._read_n(length)
return data
def _read_n(self, length):
"""Read n bytes from the socket."""
if self._socket is None:
raise TCPConnectionError(self._logprefix + 'not connected')
buf = bytes()
while length > 0:
try:
data = self._socket.recv(length)
except Exception as exception:
self._reraise_exception_as_tcp_error('failed to read data', exception)
if not data:
raise TCPConnectionError(self._logprefix + 'connection closed')
buf += data
length -= len(data)
return buf
def _reraise_exception_as_tcp_error(self, message, exception):
raise TCPConnectionError('%s%s: %s' % (self._logprefix, message, exception))

View File

@ -5,17 +5,14 @@
# For a copy, see <https://opensource.org/licenses/MIT>. # For a copy, see <https://opensource.org/licenses/MIT>.
import datetime import datetime
import sys
from contextlib import contextmanager from contextlib import contextmanager
def to_hex_str(header):
return ':'.join('{:02x}'.format(ord(c)) for c in header)
@contextmanager @contextmanager
def make_connection(client_type, *args, **kwargs): def make_connection(client_type, *args, **kwargs):
"""Context manager to create and connect a networking object.""" """Context manager to create and connect a networking client object."""
client = None client = None
try: try:
client = client_type(*args, **kwargs) client = client_type(*args, **kwargs)
@ -36,3 +33,29 @@ class StopWatch(object):
def milliseconds(self): def milliseconds(self):
return 1000.0 * (self.end - self.start).total_seconds() return 1000.0 * (self.end - self.start).total_seconds()
def to_hex_str(header):
return ':'.join('{:02x}'.format(ord(c)) for c in header)
if sys.version_info >= (3, 3):
import shutil
def print_over_same_line(text):
terminal_width = shutil.get_terminal_size((80, 20)).columns
empty_space = max(0, terminal_width - len(text))
sys.stdout.write('\r' + text + empty_space * ' ')
sys.stdout.flush()
else:
# Workaround for older Python versions.
def print_over_same_line(text):
line_length = max(print_over_same_line._last_line_length, len(text))
empty_space = max(0, line_length - len(text))
sys.stdout.write('\r' + text + empty_space * ' ')
sys.stdout.flush()
print_over_same_line._last_line_length = line_length
print_over_same_line._last_line_length = 0

View File

@ -1,241 +0,0 @@
#!/usr/bin/env python3
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
# Barcelona (UAB), and the INTEL Visual Computing Lab.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
"""Basic CARLA client example."""
from __future__ import print_function
# General Imports
import numpy as np
from PIL import Image
import random
import time
import sys
import argparse
import logging
import os
# Carla imports, Everything can be imported directly from "carla" package
from carla import CARLA
from carla import Control
from carla import Measurements
# Constant that set how offten the episodes are reseted
RESET_FREQUENCY = 100
"""
Print function, prints all the measurements saving
the images into a folder. WARNING just prints the first BGRA image
Args:
param1: The measurements dictionary to be printed
param2: The iterations
Returns:
None
Raises:
None
"""
def print_pack(measurements,i,write_images):
if write_images:
image_result = Image.fromarray( measurements['BGRA'][0])
b, g, r,a = image_result.split()
image_result = Image.merge("RGBA", (r, g, b,a))
if not os.path.exists('images'):
os.mkdir('images')
image_result.save('images/image' + str(i) + '.png')
print ('Pack ',i)
print (' Wall Time: ',measurements['WallTime'])
print (' Game Time: ',measurements['GameTime'])
print (' Player Measurements ')
print (' Position: (%f,%f,%f)' % (measurements['PlayerMeasurements'].\
transform.location.x,measurements['PlayerMeasurements'].transform.location.y,\
measurements['PlayerMeasurements'].transform.location.z ))
print (' Orientation: (%f,%f,%f)' % (measurements['PlayerMeasurements'].\
transform.orientation.x,measurements['PlayerMeasurements'].transform.orientation.y,\
measurements['PlayerMeasurements'].transform.orientation.z ))
print (' Acceleration: (%f,%f,%f)' % (measurements['PlayerMeasurements'].\
acceleration.x,measurements['PlayerMeasurements'].acceleration.y,measurements['PlayerMeasurements'].acceleration.z ))
print (' Speed: ',measurements['PlayerMeasurements'].forward_speed)
print (' Collision Vehicles (Acum. Impact): ',measurements['PlayerMeasurements'].collision_vehicles)
print (' Collision Pedestrians (Acum. Impact): ',measurements['PlayerMeasurements'].collision_pedestrians)
print (' Collision Other (Acum. Impact): ',measurements['PlayerMeasurements'].collision_other)
print (' Intersection Opposite Lane (% Volume): ',measurements['PlayerMeasurements'].intersection_otherlane)
print (' Intersection Opposite Sidewalk (% Volume): ',measurements['PlayerMeasurements'].intersection_offroad)
print (' ',len(measurements['Agents']),' Agents (Positions not printed)')
print (' ',end='')
for agent in measurements['Agents']:
if agent.HasField('vehicle'):
print ('Car',end='')
elif agent.HasField('pedestrian'):
print ('Pedestrian',end='')
elif agent.HasField('traffic_light'):
print ('Traffic Light',end='')
elif agent.HasField('speed_limit_sign'):
print ('Speed Limit Sign',end='')
print(',',end='')
print('')
def use_example(ini_file,port = 2000, host ='127.0.0.1',print_measurements =False,images_to_disk=False):
# We assume the CARLA server is already waiting for a client to connect at
# host:port. To create a connection we can use the CARLA
# constructor, it creates a CARLA client object and starts the
# connection. It will throw an exception if something goes wrong.
carla =CARLA(host,port)
""" As a first step, Carla must have a configuration file loaded. This will load a map in the server
with the properties specified by the ini file. It returns all the posible starting positions on the map
in a vector.
"""
positions = carla.loadConfigurationFile(ini_file)
"""
Ask Server for a new episode starting on position of index zero in the positions vector
"""
carla.newEpisode(0)
capture = time.time()
# General iteratior
i = 1
# Iterator that will go over the positions on the map after each episode
iterator_start_positions = 1
while True:
try:
"""
User get the measurements dictionary from the server.
Measurements contains:
* WallTime: Current time on Wall from server machine.
* GameTime: Current time on Game. Restarts at every episode
* PlayerMeasurements : All information and events that happens to player
* Agents : All non-player agents present on the map information such as cars positions, traffic light states
* BRGA : BGRA optical images
* Depth : Depth Images
* Labels : Images containing the semantic segmentation. NOTE: the semantic segmentation must be
previously activated on the server. See documentation for that.
"""
measurements = carla.getMeasurements()
# Print all the measurements... Will write images to disk
if print_measurements:
print_pack(measurements,i,images_to_disk)
"""
Sends a control command to the server
This control structue contains the following fields:
* throttle : goes from 0 to -1
* steer : goes from -1 to 1
* brake : goes from 0 to 1
* hand_brake : Activate or desactivate the Hand Brake.
* reverse: Activate or desactive the reverse gear.
"""
control = Control()
control.throttle = 0.9
control.steer = (random.random() * 2) - 1
carla.sendCommand(control)
i+=1
if i % RESET_FREQUENCY ==0:
print ('Fps for this episode : ',(1.0/((time.time() -capture)/100.0)))
"""
Starts another new episode, the episode will have the same configuration as the previous
one. In order to change configuration, the loadConfigurationFile could be called at any
time.
"""
if iterator_start_positions < len(positions):
carla.newEpisode(iterator_start_positions)
iterator_start_positions+=1
else :
carla.newEpisode(0)
iterator_start_positions = 1
print("Now Starting on Position: ",iterator_start_positions-1)
capture = time.time()
except Exception as e:
logging.exception('Exception raised to the top')
time.sleep(1)
if __name__ == "__main__" :
parser = argparse.ArgumentParser(description='Run the carla client example that connects to a server')
parser.add_argument('host', metavar='HOST', type=str, help='host to connect to')
parser.add_argument('port', metavar='PORT', type=int, help='port to connect to')
parser.add_argument("-c", "--config", help="the path for the server ini file that the client sends",type=str,default="CarlaSettings.ini")
parser.add_argument("-l", "--log", help="activate the log file",action="store_true")
parser.add_argument("-lv", "--log_verbose", help="activate log and put the log file to screen",action="store_true")
parser.add_argument("-pm", "--print", help=" prints the game measurements",action="store_true")
parser.add_argument(
'-i', '--images-to-disk',
action='store_true',
help='save images to disk')
args = parser.parse_args()
if args.log or args.log_verbose:
LOG_FILENAME = 'log_manual_control.log'
logging.basicConfig(filename=LOG_FILENAME,level=logging.DEBUG)
if args.log_verbose: # set of functions to put the logging to screen
root = logging.getLogger()
root.setLevel(logging.DEBUG)
ch = logging.StreamHandler(sys.stdout)
ch.setLevel(logging.DEBUG)
formatter = logging.Formatter('%(asctime)s - %(name)s - %(levelname)s - %(message)s')
ch.setFormatter(formatter)
root.addHandler(ch)
else:
sys.tracebacklimit=0 # Avoid huge exception messages out of debug mode
use_example(args.config,port=args.port, host=args.host,print_measurements=args.print,images_to_disk= args.images_to_disk)

View File

@ -1,337 +0,0 @@
#!/usr/bin/env python3
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
# Barcelona (UAB), and the INTEL Visual Computing Lab.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
# Keyboard controlling for carla. Please refer to carla_use_example for a
# simpler and more documented example.
"""
Welcome to CARLA manual control.
Use ARROWS or WASD keys for control.
W : throttle
S : brake
AD : steer
Q : toggle reverse
Space : hand-brake
R : restart level
STARTING in a moment...
"""
from __future__ import print_function
import argparse
import logging
import sys
import time
import numpy as np
import matplotlib.pyplot as plt
import pygame
from pygame.locals import *
from carla import CARLA
from carla import Control
def join_classes(labels_image):
classes_join = {
0: [0, 0, 0], # None
1: [70, 70, 70], # Buildings
2: [190, 153, 153], # Fences
3: [72, 0, 90], # Other
4: [220, 20, 60], # Pedestrians
5: [153, 153, 153], # Poles
6: [157, 234, 50], # RoadLines
7: [128, 64, 128], # Roads
8: [244, 35, 232], # Sidewalks
9: [107, 142, 35], # Vegetation
10: [0, 0, 255], # Vehicles
11: [102, 102, 156], # Walls
12: [220, 220, 0] # TrafficSigns
}
compressed_labels_image = np.zeros((labels_image.shape[0], labels_image.shape[1], 3))
for (key, value) in classes_join.items():
compressed_labels_image[np.where(labels_image == key)] = value
return compressed_labels_image
def grayscale_colormap(img, colormap):
"""Make colormaps from grayscale."""
cmap = plt.get_cmap(colormap)
rgba_img = cmap(img)
rgb_img = np.delete(rgba_img, 3, 2)
return rgb_img
def convert_depth(depth):
"""Convert depth to human readable format."""
depth = depth.astype(np.float32)
gray_depth = ((depth[:, :, 0] + # Red
depth[:, :, 1] * 256.0 + # Green
depth[:, :, 2] * 256.0 * 256.0)) # Blue
gray_depth /= (256.0 * 256.0 * 256.0 - 1)
color_depth = grayscale_colormap(gray_depth, 'jet') * 255
return color_depth
if sys.version_info >= (3, 3):
import shutil
def get_terminal_width():
return shutil.get_terminal_size((80, 20)).columns
else:
def get_terminal_width():
return 120
class App(object):
def __init__(
self,
port=2000,
host='127.0.0.1',
config='./CarlaSettings.ini',
resolution=(800, 600),
verbose=True):
self._running = True
self._display_surf = None
self.port = port
self.host = host
self.config = config
self.verbose = verbose
self.resolution = resolution
self.size = self.weight, self.height = resolution
self.reverse_gear = False
def on_init(self):
pygame.init()
print(__doc__)
time.sleep(3)
self._display_surf = pygame.display.set_mode(
self.size, pygame.HWSURFACE | pygame.DOUBLEBUF)
logging.debug('Started the PyGame Library')
self._running = True
self.step = 0
self.prev_step = 0
self.prev_time = time.time()
self.carla = CARLA(self.host, self.port)
positions = self.carla.loadConfigurationFile(self.config)
self.num_pos = len(positions)
print("Staring Episode on Position ", self.num_pos)
self.carla.newEpisode(np.random.randint(self.num_pos))
self.prev_restart_time = time.time()
def on_event(self, event):
if event.type == pygame.QUIT:
self._running = False
def on_loop(self):
self.step += 1
keys = pygame.key.get_pressed()
restart = False
control = Control()
pressed_keys = []
if keys[K_LEFT] or keys[K_a]:
control.steer = -1.0
pressed_keys.append('left')
if keys[K_RIGHT] or keys[K_d]:
control.steer = 1.0
pressed_keys.append('right')
if keys[K_UP] or keys[K_w]:
control.throttle = 1.0
pressed_keys.append('reverse' if self.reverse_gear else 'forward')
if keys[K_DOWN] or keys[K_s]:
control.brake = 1.0
pressed_keys.append('brake')
if keys[K_SPACE]:
control.hand_brake = True
pressed_keys.append('hand-brake')
if keys[K_q]:
self.reverse_gear = not self.reverse_gear
pressed_keys.append('toggle reverse')
if keys[K_r]:
pressed_keys.append('reset')
if time.time() - self.prev_restart_time > 2.:
self.prev_restart_time = time.time()
restart = True
if time.time() - self.prev_restart_time < 2.:
control.throttle = 0.0
control.steer = 0.0
control.reverse = self.reverse_gear
self.carla.sendCommand(control)
measurements = self.carla.getMeasurements()
pack = measurements['PlayerMeasurements']
self.img_vec = measurements['BGRA']
self.depth_vec = measurements['Depth']
self.labels_vec = measurements['Labels']
if time.time() - self.prev_time > 1.:
message = 'Step {step} ({fps:.1f} FPS): '
message += '{speed:.2f} km/h, '
message += '{other_lane:.0f}% other lane, {offroad:.0f}% off-road'
message += ': pressed [%s]' % ', '.join(pressed_keys)
message = message.format(
step=self.step,
fps=float(self.step - self.prev_step) / (time.time() - self.prev_time),
speed=pack.forward_speed,
other_lane=100 * pack.intersection_otherlane,
offroad=100 * pack.intersection_offroad)
empty_space = max(0, get_terminal_width() - len(message))
sys.stdout.write('\r' + message + empty_space * ' ')
sys.stdout.flush()
self.prev_step = self.step
self.prev_time = time.time()
if restart:
print('\n *** RESTART *** \n')
player_pos = np.random.randint(self.num_pos)
print(' Player pos %d \n' % (player_pos))
self.carla.newEpisode(player_pos)
def on_render(self):
"""
The render method plots the First RGB, the First Depth and First
Semantic Segmentation Camera.
"""
auxImgResolution = (320, 180)
auxImgYPos = self.height - auxImgResolution[1] - 25
nImages = 2
f = ((self.weight - nImages * auxImgResolution[0]) / (nImages + 1) + auxImgResolution[0])
x_pos = (self.weight - nImages * auxImgResolution[0]) / (nImages + 1)
if self.img_vec:
self.img_vec[0] = self.img_vec[0][:, :, :3]
self.img_vec[0] = self.img_vec[0][:, :, ::-1]
surface = pygame.surfarray.make_surface(
np.transpose(self.img_vec[0], (1, 0, 2)))
self._display_surf.blit(surface, (0, 0))
if self.depth_vec:
self.depth_vec[0] = self.depth_vec[0][:, :, :3]
self.depth_vec[0] = self.depth_vec[0][:, :, ::-1]
self.depth_vec[0] = convert_depth(self.depth_vec[0])
surface = pygame.surfarray.make_surface(
np.transpose(self.depth_vec[0], (1, 0, 2)))
# Resize image
auxImgXPos = (self.weight / 4) - (auxImgResolution[0] / 2)
surface = pygame.transform.scale(surface, auxImgResolution)
self._display_surf.blit(surface, (x_pos, auxImgYPos))
x_pos += f
if self.labels_vec:
self.labels_vec[0] = join_classes(self.labels_vec[0][:, :, 2])
surface = pygame.surfarray.make_surface(
np.transpose(self.labels_vec[0], (1, 0, 2)))
# Resize image
auxImgXPos = ((self.weight / 4) * 3) - (auxImgResolution[0] / 2)
surface = pygame.transform.scale(surface, auxImgResolution)
self._display_surf.blit(surface, (x_pos, auxImgYPos))
x_pos += f
pygame.display.flip()
def on_cleanup(self):
self.carla.closeConections()
pygame.quit()
def on_execute(self):
if self.on_init() == False:
self._running = False
while(self._running):
try:
for event in pygame.event.get():
self.on_event(event)
self.on_loop()
self.on_render()
except Exception as e:
logging.exception(e)
self._running = False
break
self.on_cleanup()
def main():
parser = argparse.ArgumentParser(
description='Run the carla client manual that connects to CARLA server')
parser.add_argument(
'host',
metavar='HOST',
type=str,
help='host to connect to')
parser.add_argument(
'port',
metavar='PORT',
type=int,
help='port to connect to')
parser.add_argument(
"-c",
"--config",
help="the path for the server .ini config file that the client sends",
type=str,
default="./CarlaSettings.ini")
parser.add_argument(
"-l",
"--log",
help="activate the log file",
action="store_true")
parser.add_argument(
"-lv",
"--log_verbose",
help="put the log file to screen",
action="store_true")
args = parser.parse_args()
if args.log or args.log_verbose:
LOG_FILENAME = 'log_manual_control.log'
logging.basicConfig(filename=LOG_FILENAME, level=logging.DEBUG)
if args.log_verbose: # set of functions to put the logging to screen
root = logging.getLogger()
root.setLevel(logging.DEBUG)
ch = logging.StreamHandler(sys.stdout)
ch.setLevel(logging.DEBUG)
formatter = logging.Formatter(
'%(asctime)s - %(name)s - %(levelname)s - %(message)s')
ch.setFormatter(formatter)
root.addHandler(ch)
theApp = App(port=args.port, host=args.host, config=args.config)
theApp.on_execute()
if __name__ == '__main__':
try:
main()
except KeyboardInterrupt:
print('\nCancelled by user. Bye!')

231
PythonClient/client_example.py Executable file
View File

@ -0,0 +1,231 @@
#!/usr/bin/env python3
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
# Barcelona (UAB), and the INTEL Visual Computing Lab.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
"""Basic CARLA client example."""
from __future__ import print_function
import argparse
import logging
import random
import sys
import time
from carla.client import make_carla_client
from carla.sensor import Camera
from carla.settings import CarlaSettings
from carla.tcp import TCPConnectionError
from carla.util import print_over_same_line
def run_carla_client(host, port, autopilot_on, save_images_to_disk, image_filename_format, settings_filepath):
# Here we will run 3 episodes with 300 frames each.
number_of_episodes = 3
frames_per_episode = 300
# We assume the CARLA server is already waiting for a client to connect at
# host:port. To create a connection we can use the `make_carla_client`
# context manager, it creates a CARLA client object and starts the
# connection. It will throw an exception if something goes wrong. The
# context manager makes sure the connection is always cleaned up on exit.
with make_carla_client(host, port) as client:
print('CarlaClient connected')
for episode in range(0, number_of_episodes):
# Start a new episode.
if settings_filepath is None:
# Create a CarlaSettings object. This object is a wrapper around
# the CarlaSettings.ini file. Here we set the configuration we
# want for the new episode.
settings = CarlaSettings()
settings.set(
SynchronousMode=True,
SendNonPlayerAgentsInfo=True,
NumberOfVehicles=20,
NumberOfPedestrians=40,
WeatherId=random.choice([1, 3, 7, 8, 14]))
settings.randomize_seeds()
# Now we want to add a couple of cameras to the player vehicle.
# We will collect the images produced by these cameras every
# frame.
# The default camera captures RGB images of the scene.
camera0 = Camera('CameraRGB')
# Set image resolution in pixels.
camera0.set_image_size(800, 600)
# Set its position relative to the car in centimeters.
camera0.set_position(30, 0, 130)
settings.add_sensor(camera0)
# Let's add another camera producing ground-truth depth.
camera1 = Camera('CameraDepth', PostProcessing='Depth')
camera1.set_image_size(800, 600)
camera1.set_position(30, 0, 130)
settings.add_sensor(camera1)
else:
# Alternatively, we can load these settings from a file.
with open(settings_filepath, 'r') as fp:
settings = fp.read()
# Now we load these settings into the server. The server replies
# with a scene description containing the available start spots for
# the player. Here we can provide a CarlaSettings object or a
# CarlaSettings.ini file as string.
scene = client.load_settings(settings)
# Choose one player start at random.
number_of_player_starts = len(scene.player_start_spots)
player_start = random.randint(0, max(0, number_of_player_starts - 1))
# Notify the server that we want to start the episode at the
# player_start index. This function blocks until the server is ready
# to start the episode.
print('Starting new episode...')
client.start_episode(player_start)
# Iterate every frame in the episode.
for frame in range(0, frames_per_episode):
# Read the data produced by the server this frame.
measurements, sensor_data = client.read_data()
# Print some of the measurements.
print_measurements(measurements)
# Save the images to disk if requested.
if save_images_to_disk:
for name, image in sensor_data.items():
image.save_to_disk(image_filename_format.format(episode, name, frame))
# We can access the encoded data of a given image as numpy
# array using its "data" property. For instance, to get the
# depth value (normalized) at pixel X, Y
#
# depth_array = sensor_data['CameraDepth'].data
# value_at_pixel = depth_array[Y, X]
#
# Now we have to send the instructions to control the vehicle.
# If we are in synchronous mode the server will pause the
# simulation until we send this control.
if not autopilot_on:
client.send_control(
steer=random.uniform(-1.0, 1.0),
throttle=0.5,
brake=False,
hand_brake=False,
reverse=False)
else:
# Together with the measurements, the server has sent the
# control that the in-game autopilot would do this frame. We
# can enable autopilot by sending back this control to the
# server. We can modify it if wanted, here for instance we
# will add some noise to the steer.
control = measurements.player_measurements.autopilot_control
control.steer += random.uniform(-0.1, 0.1)
client.send_control(control)
def print_measurements(measurements):
number_of_agents = len(measurements.non_player_agents)
player_measurements = measurements.player_measurements
message = 'Vehicle at ({pos_x:.1f}, {pos_y:.1f}), '
message += '{speed:.2f} km/h, '
message += 'Collision: {{vehicles={col_cars:.0f}, pedestrians={col_ped:.0f}, other={col_other:.0f}}}, '
message += '{other_lane:.0f}% other lane, {offroad:.0f}% off-road, '
message += '({agents_num:d} non-player agents in the scene)'
message = message.format(
pos_x=player_measurements.transform.location.x / 100, # cm -> m
pos_y=player_measurements.transform.location.y / 100,
speed=player_measurements.forward_speed,
col_cars=player_measurements.collision_vehicles,
col_ped=player_measurements.collision_pedestrians,
col_other=player_measurements.collision_other,
other_lane=100 * player_measurements.intersection_otherlane,
offroad=100 * player_measurements.intersection_offroad,
agents_num=number_of_agents)
print_over_same_line(message)
def main():
argparser = argparse.ArgumentParser(description=__doc__)
argparser.add_argument(
'-v', '--verbose',
action='store_true',
dest='debug',
help='print debug information')
argparser.add_argument(
'--host',
metavar='H',
default='localhost',
help='IP of the host server (default: localhost)')
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(
'-i', '--images-to-disk',
action='store_true',
help='save images to disk')
argparser.add_argument(
'-c', '--carla-settings',
metavar='PATH',
default=None,
help='Path to a "CarlaSettings.ini" file')
args = argparser.parse_args()
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)
while True:
try:
run_carla_client(
host=args.host,
port=args.port,
autopilot_on=args.autopilot,
save_images_to_disk=args.images_to_disk,
image_filename_format='_images/episode_{:0>3d}/{:s}/image_{:0>5d}.png',
settings_filepath=args.carla_settings)
print('Done.')
return
except TCPConnectionError as error:
logging.error(error)
time.sleep(1)
except Exception as exception:
logging.exception(exception)
sys.exit(1)
if __name__ == '__main__':
try:
main()
except KeyboardInterrupt:
print('\nCancelled by user. Bye!')

344
PythonClient/manual_control.py Executable file
View File

@ -0,0 +1,344 @@
#!/usr/bin/env python3
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
# Barcelona (UAB), and the INTEL Visual Computing Lab.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
# Keyboard controlling for carla. Please refer to client_example for a simpler
# and more documented example.
"""
Welcome to CARLA manual control.
Use ARROWS or WASD keys for control.
W : throttle
S : brake
AD : steer
Q : toggle reverse
Space : hand-brake
R : restart level
STARTING in a moment...
"""
from __future__ import print_function
import argparse
import logging
import random
import sys
import time
try:
import pygame
from pygame.locals import *
except ImportError:
raise RuntimeError('cannot import pygame, make sure pygame package is installed')
try:
import numpy as np
except ImportError:
raise RuntimeError('cannot import numpy, make sure numpy package is installed')
from carla import image_converter
from carla import sensor
from carla.client import make_carla_client, VehicleControl
from carla.planner.map import CarlaMap
from carla.settings import CarlaSettings
from carla.tcp import TCPConnectionError
from carla.util import print_over_same_line
WINDOW_WIDTH = 800
WINDOW_HEIGHT = 600
MINI_WINDOW_WIDTH = 320
MINI_WINDOW_HEIGHT = 180
def make_carla_settings():
"""Make a CarlaSettings object with the settings we need."""
settings = CarlaSettings()
settings.set(
SynchronousMode=False,
NumberOfVehicles=15,
NumberOfPedestrians=30,
WeatherId=random.choice([1, 3, 7, 8, 14]))
settings.randomize_seeds()
camera0 = sensor.Camera('CameraRGB')
camera0.set_image_size(WINDOW_WIDTH, WINDOW_HEIGHT)
camera0.set_position(200, 0, 140)
camera0.set_rotation(0.0, 0.0, 0.0)
settings.add_sensor(camera0)
camera1 = sensor.Camera('CameraDepth', PostProcessing='Depth')
camera1.set_image_size(MINI_WINDOW_WIDTH, MINI_WINDOW_HEIGHT)
camera1.set_position(200, 0, 140)
camera1.set_rotation(0.0, 0.0, 0.0)
settings.add_sensor(camera1)
camera2 = sensor.Camera('CameraSemSeg', PostProcessing='SemanticSegmentation')
camera2.set_image_size(MINI_WINDOW_WIDTH, MINI_WINDOW_HEIGHT)
camera2.set_position(200, 0, 140)
camera2.set_rotation(0.0, 0.0, 0.0)
settings.add_sensor(camera2)
return settings
class Timer(object):
def __init__(self):
self.step = 0
self._lap_step = 0
self._lap_time = time.time()
def tick(self):
self.step += 1
def lap(self):
self._lap_step = self.step
self._lap_time = time.time()
def ticks_per_second(self):
return float(self.step - self._lap_step) / self.elapsed_seconds_since_lap()
def elapsed_seconds_since_lap(self):
return time.time() - self._lap_time
class CarlaGame(object):
def __init__(self, carla_client, city_name=None):
self.client = carla_client
self._timer = None
self._display = None
self._main_image = None
self._mini_view_image1 = None
self._mini_view_image2 = None
self._map_view = None
self._is_on_reverse = False
self._city_name = city_name
self._map = CarlaMap(city_name) if city_name is not None else None
def execute(self):
"""Launch the PyGame."""
pygame.init()
self._initialize_game()
try:
while True:
for event in pygame.event.get():
if event.type == pygame.QUIT:
return
self._on_loop()
self._on_render()
finally:
pygame.quit()
def _initialize_game(self):
if self._city_name is not None:
self._display = pygame.display.set_mode(
(WINDOW_WIDTH * 2, WINDOW_HEIGHT),
pygame.HWSURFACE | pygame.DOUBLEBUF)
else:
self._display = pygame.display.set_mode(
(WINDOW_WIDTH, WINDOW_HEIGHT),
pygame.HWSURFACE | pygame.DOUBLEBUF)
logging.debug('pygame started')
self._on_new_episode()
def _on_new_episode(self):
scene = self.client.load_settings(make_carla_settings())
number_of_player_starts = len(scene.player_start_spots)
player_start = np.random.randint(number_of_player_starts)
print('Starting new episode...')
self.client.start_episode(player_start)
self._timer = Timer()
self._is_on_reverse = False
def _on_loop(self):
self._timer.tick()
measurements, sensor_data = self.client.read_data()
self._main_image = sensor_data['CameraRGB']
self._mini_view_image1 = sensor_data['CameraDepth']
self._mini_view_image2 = sensor_data['CameraSemSeg']
# Print measurements every second.
if self._timer.elapsed_seconds_since_lap() > 1.0:
if self._city_name is not None:
# Function to get car position on map.
map_position = self._map.get_position_on_map([
measurements.player_measurements.transform.location.x,
measurements.player_measurements.transform.location.y,
measurements.player_measurements.transform.location.z])
# Function to get orientation of the road car is in.
lane_orientation = self._map.get_lane_orientation([
measurements.player_measurements.transform.location.x,
measurements.player_measurements.transform.location.y,
measurements.player_measurements.transform.location.z])
self._print_player_measurements_map(
measurements.player_measurements,
map_position,
lane_orientation)
else:
self._print_player_measurements(measurements.player_measurements)
# Plot position on the map as well.
if self._city_name is not None:
self._map.draw_position_on_map(
measurements.player_measurements.transform.location,
[255, 0, 0, 255])
self._map_view = self._map.get_map([WINDOW_WIDTH, WINDOW_HEIGHT])
self._timer.lap()
control = self._get_keyboard_control(pygame.key.get_pressed())
if control is None:
self._on_new_episode()
else:
self.client.send_control(control)
def _get_keyboard_control(self, keys):
"""
Return a VehicleControl message based on the pressed keys. Return None
if a new episode was requested.
"""
if keys[K_r]:
return None
control = VehicleControl()
if keys[K_LEFT] or keys[K_a]:
control.steer = -1.0
if keys[K_RIGHT] or keys[K_d]:
control.steer = 1.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
if keys[K_q]:
self._is_on_reverse = not self._is_on_reverse
control.reverse = self._is_on_reverse
return control
def _print_player_measurements_map(
self,
player_measurements,
map_position,
lane_orientation):
message = 'Step {step} ({fps:.1f} FPS): '
message += 'Map Position ({map_x:.1f},{map_y:.1f}) Lane Orientation ({ori_x:.1f},{ori_y:.1f}) '
message += '{speed:.2f} km/h, '
message += '{other_lane:.0f}% other lane, {offroad:.0f}% off-road'
message = message.format(
map_x=map_position[0],
map_y=map_position[1],
ori_x=lane_orientation[0],
ori_y=lane_orientation[1],
step=self._timer.step,
fps=self._timer.ticks_per_second(),
speed=player_measurements.forward_speed,
other_lane=100 * player_measurements.intersection_otherlane,
offroad=100 * player_measurements.intersection_offroad)
print_over_same_line(message)
def _print_player_measurements(self, player_measurements):
message = 'Step {step} ({fps:.1f} FPS): '
message += '{speed:.2f} km/h, '
message += '{other_lane:.0f}% other lane, {offroad:.0f}% off-road'
message = message.format(
step=self._timer.step,
fps=self._timer.ticks_per_second(),
speed=player_measurements.forward_speed,
other_lane=100 * player_measurements.intersection_otherlane,
offroad=100 * player_measurements.intersection_offroad)
print_over_same_line(message)
def _on_render(self):
gap_x = (WINDOW_WIDTH - 2 * MINI_WINDOW_WIDTH) / 3
mini_image_y = WINDOW_HEIGHT - MINI_WINDOW_HEIGHT - gap_x
if self._main_image is not None:
array = image_converter.to_rgb_array(self._main_image)
surface = pygame.surfarray.make_surface(array.swapaxes(0, 1))
self._display.blit(surface, (0, 0))
if self._mini_view_image1 is not None:
array = image_converter.depth_to_logarithmic_grayscale(self._mini_view_image1)
surface = pygame.surfarray.make_surface(array.swapaxes(0, 1))
self._display.blit(surface, (gap_x, mini_image_y))
if self._mini_view_image2 is not None:
array = image_converter.labels_to_cityscapes_palette(
self._mini_view_image2)
surface = pygame.surfarray.make_surface(array.swapaxes(0, 1))
self._display.blit(
surface, (2 * gap_x + MINI_WINDOW_WIDTH, mini_image_y))
if self._map_view is not None:
array = self._map_view
array = array[:, :, :3]
surface = pygame.surfarray.make_surface(array)
self._display.blit(surface, (WINDOW_WIDTH, 0))
pygame.display.flip()
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='localhost',
help='IP of the host server (default: localhost)')
argparser.add_argument(
'-p', '--port',
metavar='P',
default=2000,
type=int,
help='TCP port to listen to (default: 2000)')
argparser.add_argument(
'-m', '--map-name',
metavar='M',
default=None,
help='plot the map of the current city (needs to match active map in server, options: Town01 or Town02)')
args = argparser.parse_args()
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:
with make_carla_client(args.host, args.port) as client:
game = CarlaGame(client, args.map_name)
game.execute()
break
except TCPConnectionError as error:
logging.error(error)
time.sleep(1)
except Exception as exception:
logging.exception(exception)
sys.exit(1)
if __name__ == '__main__':
try:
main()
except KeyboardInterrupt:
print('\nCancelled by user. Bye!')

View File

@ -15,8 +15,9 @@ import threading
import time import time
from .client import CarlaClient from carla.client import CarlaClient
from .settings import CarlaSettings, Camera from carla.sensor import Camera, Image
from carla.settings import CarlaSettings
class _Control(object): class _Control(object):
@ -55,7 +56,7 @@ def get_default_carla_settings(args):
NumberOfVehicles=20, NumberOfVehicles=20,
NumberOfPedestrians=40, NumberOfPedestrians=40,
WeatherId=1) WeatherId=1)
settings.add_camera(Camera('Camera1')) settings.add_sensor(Camera('Camera1'))
return str(settings) return str(settings)
@ -88,7 +89,6 @@ class CarlaClientConsole(cmd.Cmd):
self.done = False self.done = False
self.thread.start() self.thread.start()
def cleanup(self): def cleanup(self):
self.do_disconnect() self.do_disconnect()
self.done = True self.done = True
@ -129,7 +129,7 @@ class CarlaClientConsole(cmd.Cmd):
self.control = _Control() self.control = _Control()
if not self.client.connected(): if not self.client.connected():
self.client.connect() self.client.connect()
self.client.request_new_episode(self.settings) self.client.load_settings(self.settings)
self.client.start_episode(0) self.client.start_episode(0)
logging.info('new episode started') logging.info('new episode started')
except Exception as exception: except Exception as exception:
@ -165,11 +165,12 @@ class CarlaClientConsole(cmd.Cmd):
filename = '_images/console/camera_{:0>3d}/image_{:0>8d}.png' filename = '_images/console/camera_{:0>3d}/image_{:0>8d}.png'
while not self.done: while not self.done:
try: try:
measurements, images = self.client.read_measurements() measurements, sensor_data = self.client.read_data()
if self.print_measurements: if self.print_measurements:
print(measurements) print(measurements)
if self.args.images_to_disk: if self.args.images_to_disk:
images = [x for x in sensor_data.values() if isinstance(x, Image)]
for n, image in enumerate(images): for n, image in enumerate(images):
path = filename.format(n, measurements.game_timestamp) path = filename.format(n, measurements.game_timestamp)
image.save_to_disk(path) image.save_to_disk(path)

View File

@ -20,11 +20,13 @@ sys.path.append(os.path.join(os.path.dirname(__file__), '..'))
import carla import carla
from carla.client import CarlaClient from carla.client import CarlaClient
from carla.console import CarlaClientConsole from carla.sensor import Camera, Image
from carla.settings import CarlaSettings, Camera from carla.settings import CarlaSettings
from carla.tcp import TCPClient from carla.tcp import TCPClient
from carla.util import make_connection from carla.util import make_connection
import console
def run_carla_client(args): def run_carla_client(args):
with make_connection(CarlaClient, args.host, args.port, timeout=15) as client: with make_connection(CarlaClient, args.host, args.port, timeout=15) as client:
@ -39,12 +41,12 @@ def run_carla_client(args):
settings.randomize_seeds() settings.randomize_seeds()
camera = Camera('DefaultCamera') camera = Camera('DefaultCamera')
camera.set_image_size(300, 200) # Do not change this, hard-coded in test. camera.set_image_size(300, 200) # Do not change this, hard-coded in test.
settings.add_camera(camera) settings.add_sensor(camera)
logging.debug('sending CarlaSettings:\n%s', settings) logging.debug('sending CarlaSettings:\n%s', settings)
logging.info('new episode requested') logging.info('new episode requested')
scene = client.request_new_episode(settings) scene = client.load_settings(settings)
number_of_player_starts = len(scene.player_start_spots) number_of_player_starts = len(scene.player_start_spots)
player_start = random.randint(0, max(0, number_of_player_starts - 1)) player_start = random.randint(0, max(0, number_of_player_starts - 1))
@ -56,12 +58,13 @@ def run_carla_client(args):
client.start_episode(player_start) client.start_episode(player_start)
use_ai_control = (random.random() < 0.5) use_autopilot_control = (random.random() < 0.5)
reverse = (random.random() < 0.2) reverse = (random.random() < 0.2)
for frame in range(0, frames_per_episode): for frame in range(0, frames_per_episode):
logging.debug('reading measurements...') logging.debug('reading measurements...')
measurements, images = client.read_measurements() measurements, sensor_data = client.read_data()
images = [x for x in sensor_data.values() if isinstance(x, Image)]
logging.debug('received data of %d agents', len(measurements.non_player_agents)) logging.debug('received data of %d agents', len(measurements.non_player_agents))
assert len(images) == 1 assert len(images) == 1
@ -71,8 +74,8 @@ def run_carla_client(args):
images[0].save_to_disk(filename.format(episode, frame)) images[0].save_to_disk(filename.format(episode, frame))
logging.debug('sending control...') logging.debug('sending control...')
control = measurements.player_measurements.ai_control control = measurements.player_measurements.autopilot_control
if not use_ai_control: if not use_autopilot_control:
control.steer = random.uniform(-1.0, 1.0) control.steer = random.uniform(-1.0, 1.0)
control.throttle = 0.3 control.throttle = 0.3
control.hand_brake = False control.hand_brake = False
@ -140,7 +143,7 @@ def main():
logging.info('listening to server %s:%s', args.host, args.port) logging.info('listening to server %s:%s', args.host, args.port)
if args.console: if args.console:
cmd = CarlaClientConsole(args) cmd = console.CarlaClientConsole(args)
try: try:
cmd.cmdloop() cmd.cmdloop()
finally: finally:

View File

@ -23,6 +23,7 @@ sys.path.append(os.path.join(os.path.dirname(__file__), '.'))
import carla import carla
from carla.tcp import TCPConnectionError
from carla.util import StopWatch from carla.util import StopWatch
from unit_tests import CarlaServerTest from unit_tests import CarlaServerTest
@ -99,14 +100,20 @@ def run_test(test, args):
logging.error('exception instantiating %r: %s', test.name, exception) logging.error('exception instantiating %r: %s', test.name, exception)
return False return False
log_test(RUN, test.name) log_test(RUN, test.name)
try: while True:
timer = StopWatch() try:
result = test.run() timer = StopWatch()
timer.stop() result = test.run()
except Exception as exception: timer.stop()
timer.stop() break
logging.error('exception: %s', exception) except TCPConnectionError as error:
result = False logging.error(error)
time.sleep(1)
except Exception as exception:
timer.stop()
logging.exception('exception: %s', exception)
result = False
break
log_test(OK if result else FAILED, '%s (%d ms)', test.name, timer.milliseconds()) log_test(OK if result else FAILED, '%s (%d ms)', test.name, timer.milliseconds())
return result return result
@ -118,9 +125,6 @@ def do_the_tests(args):
failed = [] failed = []
log_test(SEP0, 'Running %d tests.', len(tests)) log_test(SEP0, 'Running %d tests.', len(tests))
for test in tests: for test in tests:
if succeeded or failed:
logging.info('waiting for the server to be ready again')
time.sleep(7)
if run_test(test, args): if run_test(test, args):
succeeded.append(test) succeeded.append(test)
else: else:

View File

@ -4,20 +4,21 @@
# This work is licensed under the terms of the MIT license. # This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>. # For a copy, see <https://opensource.org/licenses/MIT>.
import unit_tests
import logging import logging
import random import random
import unit_tests
import carla import carla
from carla.client import CarlaClient from carla.client import CarlaClient
from carla.settings import CarlaSettings, Camera from carla.sensor import Camera, Image
from carla.settings import CarlaSettings
from carla.util import make_connection from carla.util import make_connection
class _BasicTestBase(unit_tests.CarlaServerTest): class _BasicTestBase(unit_tests.CarlaServerTest):
def run_carla_client(self, carla_settings, number_of_episodes, number_of_frames, use_ai_control=None): def run_carla_client(self, carla_settings, number_of_episodes, number_of_frames, use_autopilot_control=None):
with make_connection(CarlaClient, self.args.host, self.args.port, timeout=15) as client: with make_connection(CarlaClient, self.args.host, self.args.port, timeout=15) as client:
logging.info('CarlaClient connected, running %d episodes', number_of_episodes) logging.info('CarlaClient connected, running %d episodes', number_of_episodes)
for _ in range(0, number_of_episodes): for _ in range(0, number_of_episodes):
@ -25,7 +26,7 @@ class _BasicTestBase(unit_tests.CarlaServerTest):
carla_settings.randomize_weather() carla_settings.randomize_weather()
logging.debug('sending CarlaSettings:\n%s', carla_settings) logging.debug('sending CarlaSettings:\n%s', carla_settings)
logging.info('new episode requested') logging.info('new episode requested')
scene = client.request_new_episode(carla_settings) scene = client.load_settings(carla_settings)
number_of_player_starts = len(scene.player_start_spots) number_of_player_starts = len(scene.player_start_spots)
player_start = random.randint(0, max(0, number_of_player_starts - 1)) player_start = random.randint(0, max(0, number_of_player_starts - 1))
logging.info( logging.info(
@ -34,20 +35,21 @@ class _BasicTestBase(unit_tests.CarlaServerTest):
number_of_player_starts, number_of_player_starts,
number_of_frames) number_of_frames)
client.start_episode(player_start) client.start_episode(player_start)
if use_ai_control is None: if use_autopilot_control is None:
use_ai_control = (random.random() < 0.5) use_autopilot_control = (random.random() < 0.5)
reverse = (random.random() < 0.2) reverse = (random.random() < 0.2)
for _ in range(0, number_of_frames): for _ in range(0, number_of_frames):
logging.debug('reading measurements...') logging.debug('reading measurements...')
measurements, images = client.read_measurements() measurements, sensor_data = client.read_data()
images = [x for x in sensor_data.values() if isinstance(x, Image)]
number_of_agents = len(measurements.non_player_agents) number_of_agents = len(measurements.non_player_agents)
logging.debug('received data of %d agents', number_of_agents) logging.debug('received data of %d agents', number_of_agents)
logging.debug('received %d images', len(images)) logging.debug('received %d images', len(images))
if len(images) != len(carla_settings._cameras): if len(images) != len(carla_settings._cameras):
raise RuntimeError('received %d images, expected %d' % (len(images), len(carla_settings._cameras))) raise RuntimeError('received %d images, expected %d' % (len(images), len(carla_settings._cameras)))
logging.debug('sending control...') logging.debug('sending control...')
control = measurements.player_measurements.ai_control control = measurements.player_measurements.autopilot_control
if not use_ai_control: if not use_autopilot_control:
control.steer = random.uniform(-1.0, 1.0) control.steer = random.uniform(-1.0, 1.0)
control.throttle = 0.3 control.throttle = 0.3
control.hand_brake = False control.hand_brake = False
@ -63,7 +65,7 @@ class _BasicTestBase(unit_tests.CarlaServerTest):
class UseCase(_BasicTestBase): class UseCase(_BasicTestBase):
def run(self): def run(self):
settings = CarlaSettings() settings = CarlaSettings()
settings.add_camera(Camera('DefaultCamera')) settings.add_sensor(Camera('DefaultCamera'))
self.run_carla_client(settings, 5, 200) self.run_carla_client(settings, 5, 200)
@ -76,18 +78,18 @@ class NoCamera(_BasicTestBase):
class TwoCameras(_BasicTestBase): class TwoCameras(_BasicTestBase):
def run(self): def run(self):
settings = CarlaSettings() settings = CarlaSettings()
settings.add_camera(Camera('DefaultCamera')) settings.add_sensor(Camera('DefaultCamera'))
camera2 = Camera('Camera2') camera2 = Camera('Camera2')
camera2.set(PostProcessing='Depth', CameraFOV=120) camera2.set(PostProcessing='Depth', CameraFOV=120)
camera2.set_image_size(1924, 1028) camera2.set_image_size(1924, 1028)
settings.add_camera(camera2) settings.add_sensor(camera2)
self.run_carla_client(settings, 3, 100) self.run_carla_client(settings, 3, 100)
class SynchronousMode(_BasicTestBase): class SynchronousMode(_BasicTestBase):
def run(self): def run(self):
settings = CarlaSettings(SynchronousMode=True) settings = CarlaSettings(SynchronousMode=True)
settings.add_camera(Camera('DefaultCamera')) settings.add_sensor(Camera('DefaultCamera'))
self.run_carla_client(settings, 3, 200) self.run_carla_client(settings, 3, 200)
@ -99,12 +101,12 @@ class GetAgentsInfo(_BasicTestBase):
SendNonPlayerAgentsInfo=True, SendNonPlayerAgentsInfo=True,
NumberOfVehicles=60, NumberOfVehicles=60,
NumberOfPedestrians=90) NumberOfPedestrians=90)
settings.add_camera(Camera('DefaultCamera')) settings.add_sensor(Camera('DefaultCamera'))
self.run_carla_client(settings, 3, 100) self.run_carla_client(settings, 3, 100)
class LongEpisode(_BasicTestBase): class LongEpisode(_BasicTestBase):
def run(self): def run(self):
settings = CarlaSettings() settings = CarlaSettings()
settings.add_camera(Camera('DefaultCamera')) settings.add_sensor(Camera('DefaultCamera'))
self.run_carla_client(settings, 1, 2000, use_ai_control=True) self.run_carla_client(settings, 1, 2000, use_autopilot_control=True)

View File

@ -311,11 +311,11 @@ CarlaServer::ErrorCode CarlaServer::SendMeasurements(
Set(player.collision_other, PlayerState.GetCollisionIntensityOther()); Set(player.collision_other, PlayerState.GetCollisionIntensityOther());
Set(player.intersection_otherlane, PlayerState.GetOtherLaneIntersectionFactor()); Set(player.intersection_otherlane, PlayerState.GetOtherLaneIntersectionFactor());
Set(player.intersection_offroad, PlayerState.GetOffRoadIntersectionFactor()); Set(player.intersection_offroad, PlayerState.GetOffRoadIntersectionFactor());
Set(player.ai_control.steer, PlayerState.GetSteer()); Set(player.autopilot_control.steer, PlayerState.GetSteer());
Set(player.ai_control.throttle, PlayerState.GetThrottle()); Set(player.autopilot_control.throttle, PlayerState.GetThrottle());
Set(player.ai_control.brake, PlayerState.GetBrake()); Set(player.autopilot_control.brake, PlayerState.GetBrake());
Set(player.ai_control.hand_brake, PlayerState.GetHandBrake()); Set(player.autopilot_control.hand_brake, PlayerState.GetHandBrake());
Set(player.ai_control.reverse, PlayerState.GetCurrentGear() < 0); Set(player.autopilot_control.reverse, PlayerState.GetCurrentGear() < 0);
TArray<carla_agent> Agents; TArray<carla_agent> Agents;
if (bSendNonPlayerAgentsInfo) { if (bSendNonPlayerAgentsInfo) {

View File

@ -139,7 +139,7 @@ extern "C" {
/** Percentage of the car off-road. */ /** Percentage of the car off-road. */
float intersection_offroad; float intersection_offroad;
/** Vehicle's AI control that would apply this frame. */ /** Vehicle's AI control that would apply this frame. */
struct carla_control ai_control; struct carla_control autopilot_control;
}; };
/* ======================================================================== */ /* ======================================================================== */

View File

@ -126,7 +126,7 @@ namespace server {
player->set_collision_other(values.player_measurements.collision_other); player->set_collision_other(values.player_measurements.collision_other);
player->set_intersection_otherlane(values.player_measurements.intersection_otherlane); player->set_intersection_otherlane(values.player_measurements.intersection_otherlane);
player->set_intersection_offroad(values.player_measurements.intersection_offroad); player->set_intersection_offroad(values.player_measurements.intersection_offroad);
Set(player->mutable_ai_control(), values.player_measurements.ai_control); Set(player->mutable_autopilot_control(), values.player_measurements.autopilot_control);
// Non-player agents. // Non-player agents.
message->clear_non_player_agents(); // we need to clear as we cache the message. message->clear_non_player_agents(); // we need to clear as we cache the message.
for (auto &agent : agents(values)) { for (auto &agent : agents(values)) {

View File

@ -111,7 +111,7 @@ message Measurements {
float intersection_otherlane = 8; float intersection_otherlane = 8;
float intersection_offroad = 9; float intersection_offroad = 9;
Control ai_control = 10; Control autopilot_control = 10;
} }
uint32 platform_timestamp = 1; uint32 platform_timestamp = 1;

View File

@ -2,16 +2,14 @@
set PROTOBUF_SRC_DIR=Proto set PROTOBUF_SRC_DIR=Proto
set PROTOBUF_CPP_OUT_DIR=CarlaServer/source/carla/server set PROTOBUF_CPP_OUT_DIR=CarlaServer/source/carla/server
set PROTOBUF_PY_OUT_DIR0=../PythonClient/carla/protoc set PROTOBUF_PY_OUT_DIR=../PythonClient/carla
set PROTOBUF_PY_OUT_DIR1=TestingClient/carla
set PROTO_BASENAME=carla_server set PROTO_BASENAME=carla_server
if "%1" == "--clean" ( if "%1" == "--clean" (
rem Delete existing ones. rem Delete existing ones.
rm -f %PROTOBUF_CPP_OUT_DIR%/carla_server.pb.h rm -f %PROTOBUF_CPP_OUT_DIR%/carla_server.pb.h
rm -f %PROTOBUF_CPP_OUT_DIR%/carla_server.pb.cc rm -f %PROTOBUF_CPP_OUT_DIR%/carla_server.pb.cc
rm -f %PROTOBUF_PY_OUT_DIR0%/carla_server_pb2.py rm -f %PROTOBUF_PY_OUT_DIR%/carla_server_pb2.py
rm -f %PROTOBUF_PY_OUT_DIR1%/carla_server_pb2.py
goto end goto end
) )
@ -24,8 +22,7 @@ if exist %PROTOC% (
%PROTOC% ^ %PROTOC% ^
-I=%PROTOBUF_SRC_DIR% ^ -I=%PROTOBUF_SRC_DIR% ^
--cpp_out=%PROTOBUF_CPP_OUT_DIR% ^ --cpp_out=%PROTOBUF_CPP_OUT_DIR% ^
--python_out=%PROTOBUF_PY_OUT_DIR0% ^ --python_out=%PROTOBUF_PY_OUT_DIR% ^
--python_out=%PROTOBUF_PY_OUT_DIR1% ^
%PROTOBUF_SRC_DIR%/%PROTO_BASENAME%.proto %PROTOBUF_SRC_DIR%/%PROTO_BASENAME%.proto
echo done. echo done.

View File

@ -7,15 +7,13 @@ pushd "$SCRIPT_DIR" >/dev/null
PROTOBUF_SRC_DIR=Proto PROTOBUF_SRC_DIR=Proto
PROTOBUF_CPP_OUT_DIR=CarlaServer/source/carla/server PROTOBUF_CPP_OUT_DIR=CarlaServer/source/carla/server
PROTOBUF_PY_OUT_DIR0=../PythonClient/carla/protoc PROTOBUF_PY_OUT_DIR=../PythonClient/carla
PROTOBUF_PY_OUT_DIR1=TestingClient/carla
PROTO_BASENAME=carla_server PROTO_BASENAME=carla_server
if [ "$1" == "--clean" ]; then if [ "$1" == "--clean" ]; then
# Delete existing ones. # Delete existing ones.
rm -f ${PROTOBUF_CPP_OUT_DIR}/*.pb.h ${PROTOBUF_CPP_OUT_DIR}/*.pb.cc rm -f ${PROTOBUF_CPP_OUT_DIR}/*.pb.h ${PROTOBUF_CPP_OUT_DIR}/*.pb.cc
rm -f ${PROTOBUF_PY_OUT_DIR0}/*_pb2.py rm -f ${PROTOBUF_PY_OUT_DIR}/*_pb2.py
rm -f ${PROTOBUF_PY_OUT_DIR1}/*_pb2.py
exit 0 exit 0
fi fi
@ -33,8 +31,7 @@ echo "Compiling ${PROTO_BASENAME}.proto..."
${PROTOC} \ ${PROTOC} \
-I=${PROTOBUF_SRC_DIR} \ -I=${PROTOBUF_SRC_DIR} \
--cpp_out=${PROTOBUF_CPP_OUT_DIR} \ --cpp_out=${PROTOBUF_CPP_OUT_DIR} \
--python_out=${PROTOBUF_PY_OUT_DIR0} \ --python_out=${PROTOBUF_PY_OUT_DIR} \
--python_out=${PROTOBUF_PY_OUT_DIR1} \
${PROTOBUF_SRC_DIR}/${PROTO_BASENAME}.proto ${PROTOBUF_SRC_DIR}/${PROTO_BASENAME}.proto
popd >/dev/null popd >/dev/null

View File

@ -1,12 +0,0 @@
CARLA Client for Testing
========================
Requires Python 3 and the protobuf module installed, saving images to disk
requires the PIL module too.
$ sudo apt-get install python3 python3-pip
$ sudo pip3 install protobuf
A sample Python script explaining how to use the client API is provided
$ ./client_example.py --help

View File

@ -1,161 +0,0 @@
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
# Barcelona (UAB), and the INTEL Visual Computing Lab.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
"""CARLA Client."""
import os
import struct
from contextlib import contextmanager
from . import tcp
from . import util
try:
from . import carla_server_pb2 as carla_protocol
except ImportError:
raise RuntimeError('cannot import "carla_server_pb2.py", run the protobuf compiler to generate this file')
@contextmanager
def make_carla_client(host, world_port, timeout=15):
with util.make_connection(CarlaClient, host, world_port, timeout) as client:
yield client
class CarlaClient(object):
def __init__(self, host, world_port, timeout=15):
self._world_client = tcp.TCPClient(host, world_port, timeout)
self._stream_client = tcp.TCPClient(host, world_port + 1, timeout)
self._control_client = tcp.TCPClient(host, world_port + 2, timeout)
def connect(self):
self._world_client.connect()
def disconnect(self):
self._control_client.disconnect()
self._stream_client.disconnect()
self._world_client.disconnect()
def connected(self):
return self._world_client.connected()
def request_new_episode(self, carla_settings):
"""Request a new episode. carla_settings object must be convertible to
a str holding a CarlaSettings.ini.
Returns a protobuf object holding the scene description.
"""
# Disconnect agent clients.
self._stream_client.disconnect()
self._control_client.disconnect()
# Send new episode request.
pb_message = carla_protocol.RequestNewEpisode()
pb_message.ini_file = str(carla_settings)
self._world_client.write(pb_message.SerializeToString())
# Read scene description.
data = self._world_client.read()
if not data:
raise RuntimeError('failed to read data from server')
pb_message = carla_protocol.SceneDescription()
pb_message.ParseFromString(data)
if len(pb_message.player_start_spots) < 1:
raise RuntimeError("received 0 player start spots")
return pb_message
def start_episode(self, player_start_index):
"""Start the new episode at the player start given by the
player_start_index. The list of player starts is retrieved by
request_new_episode().
This function waits until the server answers with an EpisodeReady.
"""
pb_message = carla_protocol.EpisodeStart()
pb_message.player_start_spot_index = player_start_index
self._world_client.write(pb_message.SerializeToString())
# Wait for EpisodeReady.
data = self._world_client.read()
if not data:
raise RuntimeError('failed to read data from server')
pb_message = carla_protocol.EpisodeReady()
pb_message.ParseFromString(data)
if not pb_message.ready:
raise RuntimeError('cannot start episode: server failed to start episode')
# We can start the agent clients now.
self._stream_client.connect()
self._control_client.connect()
def read_measurements(self):
"""Read measuremnts of current frame. The episode must be started.
Return the protobuf object with the measurements followed by the raw
data with the images.
"""
# Read measurements.
data = self._stream_client.read()
if not data:
raise RuntimeError('failed to read data from server')
pb_message = carla_protocol.Measurements()
pb_message.ParseFromString(data)
# Read images.
images_raw_data = self._stream_client.read()
return pb_message, CarlaImage.parse_raw_data(images_raw_data)
def send_control(self, *args, **kwargs):
"""Send vehicle control for the current frame."""
if isinstance(args[0] if args else None, carla_protocol.Control):
pb_message = args[0]
else:
pb_message = carla_protocol.Control()
pb_message.steer = kwargs.get('steer', 0.0)
pb_message.throttle = kwargs.get('throttle', 0.0)
pb_message.brake = kwargs.get('brake', 0.0)
pb_message.hand_brake = kwargs.get('hand_brake', False)
pb_message.reverse = kwargs.get('reverse', False)
self._control_client.write(pb_message.SerializeToString())
class CarlaImage(object):
@staticmethod
def parse_raw_data(raw_data):
getval = lambda index: struct.unpack('<L', raw_data[index*4:index*4+4])[0]
images = []
total_size = len(raw_data) / 4
index = 0
while index < total_size:
width = getval(index)
height = getval(index + 1)
image_type = getval(index + 2)
begin = index + 3
end = begin + width * height
images.append(CarlaImage(width, height, image_type, raw_data[begin*4:end*4]))
index = end
return images
def __init__(self, width, height, image_type, raw_data):
assert len(raw_data) == 4 * width * height
self.width = width
self.height = height
self.image_type = image_type
self.raw = raw_data
def save_to_disk(self, filename):
try:
from PIL import Image
except ImportError:
raise RuntimeError('cannot import PIL, make sure pillow package is installed')
image = Image.frombytes(
mode='RGBA',
size=(self.width, self.height),
data=self.raw,
decoder_name='raw')
b, g, r, a = image.split()
image = Image.merge("RGB", (r, g, b))
folder = os.path.dirname(filename)
if not os.path.isdir(folder):
os.makedirs(folder)
image.save(filename)

View File

@ -1,62 +0,0 @@
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
# Barcelona (UAB), and the INTEL Visual Computing Lab.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
"""Basic TCP client."""
import logging
import socket
import struct
class TCPClient(object):
def __init__(self, host, port, timeout):
self._host = host
self._port = port
self._timeout = timeout
self._socket = None
def connect(self):
self._socket = socket.create_connection(address=(self._host, self._port), timeout=self._timeout)
self._socket.settimeout(self._timeout)
self._log('connected')
def disconnect(self):
if self._socket is not None:
self._log('disconnecting...')
self._socket.close()
self._socket = None
def connected(self):
return self._socket is not None
def write(self, message):
if self._socket is None:
raise RuntimeError('%s:%s not connected' % (self._host, self._port))
header = struct.pack('<L', len(message))
self._socket.sendall(header + message)
def read(self):
header = self._read_n(4)
if not header:
raise RuntimeError('%s:%s connection closed' % (self._host, self._port))
length = struct.unpack('<L', header)[0]
data = self._read_n(length)
return data
def _read_n(self, length):
if self._socket is None:
raise RuntimeError('%s:%s not connected' % (self._host, self._port))
buf = bytes()
while length > 0:
data = self._socket.recv(length)
if not data:
raise RuntimeError('%s:%s connection closed' % (self._host, self._port))
buf += data
length -= len(data)
return buf
def _log(self, message, *args):
logging.debug('tcpclient %s:%d - ' + message, self._host, self._port, *args)

View File

@ -1,215 +0,0 @@
#!/usr/bin/env python3
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
# Barcelona (UAB), and the INTEL Visual Computing Lab.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
"""Basic CARLA client example."""
import argparse
import logging
import random
import shutil
import sys
import time
from carla.client import make_carla_client
from carla.console import CarlaClientConsole
from carla.settings import CarlaSettings, Camera
def run_carla_client(host, port, autopilot_on, save_images_to_disk, image_filename_format):
# Here we will run 3 episodes with 300 frames each.
number_of_episodes = 3
frames_per_episode = 300
# We assume the CARLA server is already waiting for a client to connect at
# host:port. To create a connection we can use the `make_carla_client`
# context manager, it creates a CARLA client object and starts the
# connection. It will throw an exception if something goes wrong. The
# context manager makes sure the connection is always cleaned up on exit.
with make_carla_client(host, port) as client:
print('CarlaClient connected')
for episode in range(0, number_of_episodes):
# Start a new episode.
# Create a CarlaSettings object. This object is a handy wrapper
# around the CarlaSettings.ini file. Here we set the configuration
# we want for the new episode.
settings = CarlaSettings()
settings.set(
SynchronousMode=True,
NumberOfVehicles=30,
NumberOfPedestrians=50,
WeatherId=random.choice([1, 3, 7, 8, 14]))
settings.randomize_seeds()
# Now we want to add a couple of cameras to the player vehicle. We
# will collect the images produced by these cameras every frame.
# The default camera captures RGB images of the scene.
camera0 = Camera('CameraRGB')
# Set image resolution in pixels.
camera0.set_image_size(800, 600)
# Set its position relative to the car in centimeters.
camera0.set_position(30, 0, 130)
settings.add_camera(camera0)
# Let's add another camera producing ground-truth depth.
camera1 = Camera('CameraDepth', PostProcessing='Depth')
camera1.set_image_size(800, 600)
camera1.set_position(30, 0, 130)
settings.add_camera(camera1)
print('Requesting new episode...')
# Now we request a new episode with these settings. The server
# replies with a scene description containing the available start
# spots for the player. Here instead of a CarlaSettings object we
# could also provide a CarlaSettings.ini file as string.
scene = client.request_new_episode(settings)
# Choose one player start at random.
number_of_player_starts = len(scene.player_start_spots)
player_start = random.randint(0, max(0, number_of_player_starts - 1))
# Notify the server that we want to start the episode at
# `player_start`. This function blocks until the server is ready to
# start the episode.
client.start_episode(player_start)
# Iterate every frame in the episode.
for frame in range(0, frames_per_episode):
# Read the measurements and images produced by the server this
# frame.
measurements, images = client.read_measurements()
# Print some of the measurements we received.
print_player_measurements(measurements.player_measurements)
# Save the images to disk if requested.
if save_images_to_disk:
for n, image in enumerate(images):
image.save_to_disk(image_filename_format.format(episode, n, frame))
# Now we have to send the instructions to control the vehicle.
# If we are in synchronous mode the server will pause the
# simulation until we send this control.
if not autopilot_on:
client.send_control(
steer=random.uniform(-1.0, 1.0),
throttle=0.3,
brake=False,
hand_brake=False,
reverse=False)
else:
# Together with the measurements, the server has sent the
# control that the in-game AI would do this frame. We can
# enable autopilot by sending back this control to the
# server. Here we will also add some noise to the steer.
control = measurements.player_measurements.ai_control
control.steer += random.uniform(-0.1, 0.1)
client.send_control(control)
print('Done.')
return True
def print_player_measurements(player_measurements):
message = 'Vehicle at ({pos_x:.1f}, {pos_y:.1f}, {pos_z:.1f}) '
message += '{speed:.2f} km/h, '
message += '{other_lane:.0f}% other lane, {offroad:.0f}% off-road'
message = message.format(
pos_x=player_measurements.transform.location.x / 100, # cm -> m
pos_y=player_measurements.transform.location.y / 100,
pos_z=player_measurements.transform.location.z / 100,
speed=player_measurements.forward_speed,
other_lane=100 * player_measurements.intersection_otherlane,
offroad=100 * player_measurements.intersection_offroad)
empty_space = shutil.get_terminal_size((80, 20)).columns - len(message)
sys.stdout.write('\r' + message + empty_space * ' ')
sys.stdout.flush()
def main():
argparser = argparse.ArgumentParser(description=__doc__)
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: 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(
'-i', '--images-to-disk',
action='store_true',
help='save images to disk')
argparser.add_argument(
'-c', '--console',
action='store_true',
help='start the client console')
args = argparser.parse_args()
log_level = logging.DEBUG if args.debug else logging.INFO
logging.basicConfig(format='carla_client: %(levelname)s: %(message)s', level=log_level)
logging.info('listening to server %s:%s', args.host, args.port)
if args.console:
args.synchronous = True
cmd = CarlaClientConsole(args)
try:
cmd.cmdloop()
finally:
cmd.cleanup()
return
while True:
try:
end = run_carla_client(
host=args.host,
port=args.port,
autopilot_on=args.autopilot,
save_images_to_disk=args.images_to_disk,
image_filename_format='_images/episode_{:0>3d}/camera_{:0>3d}/image_{:0>5d}.png')
if end:
return
except Exception as exception:
logging.error('exception: %s', exception)
time.sleep(1)
if __name__ == '__main__':
try:
main()
except KeyboardInterrupt:
print('\nCancelled by user. Bye!')