Update client to new sensor interface

This commit is contained in:
nsubiron 2018-02-24 19:13:12 +01:00
parent 33c6d06ed0
commit 2da42dae40
9 changed files with 220 additions and 305 deletions

View File

@ -138,7 +138,7 @@ class CoRL2017(Benchmark):
# This single RGB camera is used on every experiment # This single RGB camera is used on every experiment
camera = Camera('CameraRGB') camera = Camera('CameraRGB')
camera.set(CameraFOV=100) camera.set(FOV=100)
camera.set_image_size(800, 600) camera.set_image_size(800, 600)

View File

@ -11,7 +11,6 @@ import struct
from contextlib import contextmanager from contextlib import contextmanager
from . import sensor from . import sensor
from . import settings
from . import tcp from . import tcp
from . import util from . import util
@ -20,6 +19,11 @@ try:
except ImportError: except ImportError:
raise RuntimeError('cannot import "carla_server_pb2.py", run the protobuf compiler to generate this file') raise RuntimeError('cannot import "carla_server_pb2.py", run the protobuf compiler to generate this file')
try:
import numpy
except ImportError:
raise RuntimeError('cannot import numpy, make sure numpy package is installed.')
VehicleControl = carla_protocol.Control VehicleControl = carla_protocol.Control
@ -40,7 +44,7 @@ class CarlaClient(object):
self._control_client = tcp.TCPClient(host, world_port + 2, timeout) self._control_client = tcp.TCPClient(host, world_port + 2, timeout)
self._current_settings = None self._current_settings = None
self._is_episode_requested = False self._is_episode_requested = False
self._sensor_names = [] self._sensors = {}
def connect(self, connection_attempts=10): def connect(self, connection_attempts=10):
""" """
@ -69,7 +73,6 @@ class CarlaClient(object):
self._current_settings = carla_settings self._current_settings = carla_settings
return self._request_new_episode(carla_settings) return self._request_new_episode(carla_settings)
def start_episode(self, player_start_index): def start_episode(self, player_start_index):
""" """
Start the new episode at the player start given by the Start the new episode at the player start given by the
@ -120,8 +123,7 @@ class CarlaClient(object):
pb_message = carla_protocol.Measurements() pb_message = carla_protocol.Measurements()
pb_message.ParseFromString(data) pb_message.ParseFromString(data)
# Read sensor data. # Read sensor data.
raw_sensor_data = self._stream_client.read() return pb_message, dict(x for x in self._read_sensor_data())
return pb_message, self._parse_raw_sensor_data(raw_sensor_data)
def send_control(self, *args, **kwargs): def send_control(self, *args, **kwargs):
""" """
@ -159,40 +161,66 @@ class CarlaClient(object):
raise RuntimeError('failed to read data from server') raise RuntimeError('failed to read data from server')
pb_message = carla_protocol.SceneDescription() pb_message = carla_protocol.SceneDescription()
pb_message.ParseFromString(data) pb_message.ParseFromString(data)
self._sensor_names = settings.get_sensor_names(carla_settings) self._sensors = dict((sensor.id, sensor) \
for sensor in _make_sensor_parsers(pb_message.sensors))
self._is_episode_requested = True self._is_episode_requested = True
return pb_message return pb_message
def _parse_raw_sensor_data(self, raw_data): def _read_sensor_data(self):
"""Return a dict of {'sensor_name': sensor_data, ...}.""" while True:
return dict((name, data) for name, data in zip( data = self._stream_client.read()
self._sensor_names, if not data:
self._iterate_sensor_data(raw_data))) raise StopIteration
yield self._parse_sensor_data(data)
@staticmethod def _parse_sensor_data(self, data):
def _iterate_sensor_data(raw_data): sensor_id = struct.unpack('<L', data[0:4])[0]
image_types = ['None', 'SceneFinal', 'Depth', 'SemanticSegmentation', 'Lidar'] parser = self._sensors[sensor_id]
gettype = lambda id: image_types[id] if len(image_types) > id else 'Unknown' return parser.name, parser.parse_raw_data(data[4:])
getint = lambda index: struct.unpack('<L', raw_data[index*4:index*4+4])[0]
getfloat = lambda index: struct.unpack('<f', raw_data[index*4:index*4+4])[0]
getdouble = lambda index: struct.unpack('<d', raw_data[index*4:index*4+8])[0] def _make_sensor_parsers(sensors):
total_size = len(raw_data) / 4 image_types = ['None', 'SceneFinal', 'Depth', 'SemanticSegmentation']
index = 0 getimgtype = lambda id: image_types[id] if len(image_types) > id else 'Unknown'
while index < total_size: getint = lambda data, index: struct.unpack('<L', data[index*4:index*4+4])[0]
sensor_type = gettype(getint(index + 2)) getfloat = lambda data, index: struct.unpack('<f', data[index*4:index*4+4])[0]
if sensor_type == 'Lidar':
horizontal_angle = getdouble(index) def parse_image(data):
channels_count = getint(index + 3) width = getint(data, 0)
lm = sensor.LidarMeasurement( height = getint(data, 1)
horizontal_angle, channels_count, image_type = getimgtype(getint(data, 2))
sensor_type, raw_data[index*4:]) fov = getfloat(data, 3)
index += lm.size_in_bytes return sensor.Image(width, height, image_type, fov, data[16:])
yield lm
def parse_lidar(data):
horizontal_angle = getfloat(data, 0)
channels_count = getint(data, 1)
points_count_by_channel = numpy.frombuffer(
data[8:8+channels_count*4],
dtype=numpy.dtype('uint32'))
points = numpy.frombuffer(
data[8+channels_count*4:],
dtype=numpy.dtype('f4'))
points = numpy.reshape(points, (int(points.shape[0]/3), 3))
return sensor.LidarMeasurement(
horizontal_angle,
channels_count,
points_count_by_channel,
sensor.PointCloud(points))
class SensorDefinition(object):
def __init__(self, s):
self.id = s.id
self.name = s.name
self.type = s.type
self.parse_raw_data = lambda x: x
for s in sensors:
sensor_def = SensorDefinition(s)
if sensor_def.type == carla_protocol.Sensor.UNKNOWN:
pass
elif sensor_def.type == carla_protocol.Sensor.LIDAR_RAY_TRACE:
sensor_def.parse_raw_data = parse_lidar
else: else:
width = getint(index) sensor_def.parse_raw_data = parse_image
height = getint(index + 1) yield sensor_def
fov = getfloat(index + 3)
begin = index + 4
end = begin + width * height
index = end
yield sensor.Image(width, height, sensor_type, fov, raw_data[begin*4:end*4])

View File

@ -13,8 +13,7 @@ import os
try: try:
import numpy import numpy
except ImportError: except ImportError:
raise RuntimeError( raise RuntimeError('cannot import numpy, make sure numpy package is installed.')
'cannot import numpy, make sure numpy package is installed.')
from collections import namedtuple from collections import namedtuple
from .transform import Transform, Translation, Rotation, Scale from .transform import Transform, Translation, Rotation, Scale
@ -42,12 +41,51 @@ class Sensor(object):
Base class for sensor descriptions. Used to add sensors to CarlaSettings. Base class for sensor descriptions. Used to add sensors to CarlaSettings.
""" """
def __init__(self, name, sensor_type):
self.SensorName = name
self.SensorType = sensor_type
self.PositionX = 140
self.PositionY = 0
self.PositionZ = 140
self.RotationPitch = 0
self.RotationRoll = 0
self.RotationYaw = 0
def set(self, **kwargs): def set(self, **kwargs):
for key, value in kwargs.items(): for key, value in kwargs.items():
if not hasattr(self, key): if not hasattr(self, key):
raise ValueError('CarlaSettings.Camera: no key named %r' % key) raise ValueError('sensor.Sensor: no key named %r' % key)
setattr(self, key, value) setattr(self, key, value)
def set_position(self, x, y, z):
self.PositionX = x
self.PositionY = y
self.PositionZ = z
def set_rotation(self, pitch, yaw, roll):
self.RotationPitch = pitch
self.RotationYaw = yaw
self.RotationRoll = roll
def get_transform(self):
'''
Returns the camera to [whatever the camera is attached to]
transformation.
'''
return Transform(
Translation(self.PositionX, self.PositionY, self.PositionZ),
Rotation(self.RotationPitch, self.RotationYaw, self.RotationRoll))
def get_unreal_transform(self):
'''
Returns the camera to [whatever the camera is attached to]
transformation with the Unreal necessary corrections applied.
@todo Do we need to expose this?
'''
to_unreal_transform = Transform(Rotation(roll=-90, yaw=90), Scale(x=-1))
return self.get_transform() * to_unreal_transform
class Camera(Sensor): class Camera(Sensor):
""" """
@ -56,17 +94,11 @@ class Camera(Sensor):
""" """
def __init__(self, name, **kwargs): def __init__(self, name, **kwargs):
self.CameraName = name super(Camera, self).__init__(name, sensor_type="CAMERA")
self.PostProcessing = 'SceneFinal' self.PostProcessing = 'SceneFinal'
self.ImageSizeX = 800 self.ImageSizeX = 800
self.ImageSizeY = 600 self.ImageSizeY = 600
self.CameraFOV = 90 self.FOV = 90
self.CameraPositionX = 140
self.CameraPositionY = 0
self.CameraPositionZ = 140
self.CameraRotationPitch = 0
self.CameraRotationRoll = 0
self.CameraRotationYaw = 0
self.set(**kwargs) self.set(**kwargs)
def set_image_size(self, pixels_x, pixels_y): def set_image_size(self, pixels_x, pixels_y):
@ -74,51 +106,6 @@ class Camera(Sensor):
self.ImageSizeX = pixels_x self.ImageSizeX = pixels_x
self.ImageSizeY = pixels_y self.ImageSizeY = pixels_y
def set_position(self, x, y, z):
'''Sets a position to the camera in cm'''
self.CameraPositionX = x
self.CameraPositionY = y
self.CameraPositionZ = z
def set_rotation(self, pitch, yaw, roll):
'''Sets a rotation to the camera'''
self.CameraRotationPitch = pitch
self.CameraRotationYaw = yaw
self.CameraRotationRoll = roll
def get_transform(self):
'''
Returns the camera to [whatever the camera is
attached to] transformation.
'''
return Transform(
Translation(
self.CameraPositionX,
self.CameraPositionY,
self.CameraPositionZ
),
Rotation(
self.CameraRotationPitch,
self.CameraRotationYaw,
self.CameraRotationRoll
)
)
def get_unreal_transform(self):
'''
Returns the camera to [whatever the camera is
attached to] transformation with the Unreal
necessary corrections applied.
'''
# Do the custom transformations.
to_unreal_transform = Transform(
Rotation(roll=-90, yaw=90),
Scale(x=-1)
)
# Apply and return it.
return self.get_transform() * to_unreal_transform
class Lidar(Sensor): class Lidar(Sensor):
""" """
@ -127,43 +114,16 @@ class Lidar(Sensor):
""" """
def __init__(self, name, **kwargs): def __init__(self, name, **kwargs):
self.LidarName = name super(Lidar, self).__init__(name, sensor_type="LIDAR_RAY_TRACE")
# Number of lasers
self.Channels = 32 self.Channels = 32
# Measure distance
self.Range = 5000 self.Range = 5000
# Points generated by all lasers per second
self.PointsPerSecond = 100000 self.PointsPerSecond = 100000
# Lidar rotation frequency
self.RotationFrequency = 10 self.RotationFrequency = 10
# Upper laser angle, counts from horizontal,
# positive values means above horizontal line
self.UpperFovLimit = 10 self.UpperFovLimit = 10
# Lower laser angle, counts from horizontal,
# negative values means under horizontal line
self.LowerFovLimit = -30 self.LowerFovLimit = -30
# wether to show debug points of laser hits in simulator
self.ShowDebugPoints = False self.ShowDebugPoints = False
# Position relative to the player.
self.LidarPositionX = 0
self.LidarPositionY = 0
self.LidarPositionZ = 250
# Rotation relative to the player.
self.LidarRotationPitch = 0
self.LidarRotationRoll = 0
self.LidarRotationYaw = 0
self.set(**kwargs) self.set(**kwargs)
def set_position(self, x, y, z):
self.LidarPositionX = x
self.LidarPositionY = y
self.LidarPositionZ = z
def set_rotation(self, pitch, roll, yaw):
self.LidarRotationPitch = pitch
self.LidarRotationRoll = roll
self.LidarRotationYaw = yaw
# ============================================================================== # ==============================================================================
# -- SensorData ---------------------------------------------------------- # -- SensorData ----------------------------------------------------------
@ -339,57 +299,24 @@ class PointCloud(SensorData):
class LidarMeasurement(SensorData): class LidarMeasurement(SensorData):
"""Data generated by a Lidar.""" """Data generated by a Lidar."""
def __init__(self, horizontal_angle, channels_count, lidar_type, raw_data): def __init__(self, horizontal_angle, channels, points_count_by_channel, point_cloud):
assert numpy.sum(points_count_by_channel) == len(point_cloud.array)
self.horizontal_angle = horizontal_angle self.horizontal_angle = horizontal_angle
self.channels_count = channels_count self.channels_count = channels
self.type = lidar_type self.points_count_by_channel = points_count_by_channel
self._converted_data = None self.point_cloud = point_cloud
points_count_by_channel_size = channels_count * 4
points_count_by_channel_bytes = raw_data[4*4:4*4 + points_count_by_channel_size]
self.points_count_by_channel = numpy.frombuffer(points_count_by_channel_bytes, dtype=numpy.dtype('uint32'))
self.points_size = int(numpy.sum(self.points_count_by_channel) * 3 * 8) # three floats X, Y, Z
begin = 4*4 + points_count_by_channel_size # 4*4 is horizontal_angle, type, channels_count
end = begin + self.points_size
self.points_data = raw_data[begin:end]
self._data_size = 4*4 + points_count_by_channel_size + self.points_size
@property
def size_in_bytes(self):
return self._data_size
@property @property
def data(self): def data(self):
"""The numpy array holding the point-cloud.
3D points format for n elements:
[ [X0,Y0,Z0],
...,
[Xn,Yn,Zn] ]
""" """
Lazy initialization for data property, stores converted data in its return self.point_cloud.array
default format.
"""
if self._converted_data is None:
points_in_one_channel = self.points_count_by_channel[0]
points = numpy.frombuffer(self.points_data[:self.points_size], dtype='float')
points = numpy.reshape(points, (self.channels_count, points_in_one_channel, 3))
self._converted_data = {
'horizontal_angle' : self.horizontal_angle,
'channels_count' : self.channels_count,
'points_count_by_channel' : self.points_count_by_channel,
'points' : points
}
return self._converted_data
def save_to_disk(self, filename): def save_to_disk(self, filename):
"""Save lidar measurements to disk""" """Save point-cloud to disk as PLY format."""
folder = os.path.dirname(filename) self.point_cloud.save_to_disk(filename)
if not os.path.isdir(folder):
os.makedirs(folder)
with open(filename, 'wt') as f:
f.write(json.dumps({
'horizontal_angle' : self.horizontal_angle,
'channels_count' : self.channels_count,
'points_count_by_channel' : self.points_count_by_channel.tolist(),
'points' : self.data['points'].tolist()
}))

View File

@ -45,8 +45,7 @@ class CarlaSettings(object):
self.SeedPedestrians = None self.SeedPedestrians = None
self.randomize_weather() self.randomize_weather()
self.set(**kwargs) self.set(**kwargs)
self._cameras = [] self._sensors = []
self._lidars = []
def set(self, **kwargs): def set(self, **kwargs):
for key, value in kwargs.items(): for key, value in kwargs.items():
@ -68,12 +67,9 @@ class CarlaSettings(object):
def add_sensor(self, sensor): def add_sensor(self, sensor):
"""Add a sensor to the player vehicle (see sensor.py).""" """Add a sensor to the player vehicle (see sensor.py)."""
if isinstance(sensor, carla_sensor.Camera): if not isinstance(sensor, carla_sensor.Sensor):
self._cameras.append(sensor)
elif isinstance(sensor, carla_sensor.Lidar):
self._lidars.append(sensor)
else:
raise ValueError('Sensor not supported') raise ValueError('Sensor not supported')
self._sensors.append(sensor)
def __str__(self): def __str__(self):
"""Converts this object to an INI formatted string.""" """Converts this object to an INI formatted string."""
@ -81,7 +77,10 @@ class CarlaSettings(object):
ini.optionxform = str ini.optionxform = str
S_SERVER = 'CARLA/Server' S_SERVER = 'CARLA/Server'
S_LEVEL = 'CARLA/LevelSettings' S_LEVEL = 'CARLA/LevelSettings'
S_CAPTURE = 'CARLA/SceneCapture' S_SENSOR = 'CARLA/Sensor'
def get_attribs(obj):
return [a for a in dir(obj) if not a.startswith('_') and not callable(getattr(obj, a))]
def add_section(section, obj, keys): def add_section(section, obj, keys):
for key in keys: for key in keys:
@ -100,38 +99,12 @@ class CarlaSettings(object):
'SeedVehicles', 'SeedVehicles',
'SeedPedestrians']) 'SeedPedestrians'])
ini.add_section(S_CAPTURE) ini.add_section(S_SENSOR)
ini.set(S_CAPTURE, 'Cameras', ','.join(c.CameraName for c in self._cameras)) ini.set(S_SENSOR, 'Sensors', ','.join(s.SensorName for s in self._sensors))
ini.set(S_CAPTURE, 'Lidars', ','.join(l.LidarName for l in self._lidars))
for camera in self._cameras: for sensor_def in self._sensors:
add_section(S_CAPTURE + '/' + camera.CameraName, camera, [ section = S_SENSOR + '/' + sensor_def.SensorName
'PostProcessing', add_section(section, sensor_def, get_attribs(sensor_def))
'ImageSizeX',
'ImageSizeY',
'CameraFOV',
'CameraPositionX',
'CameraPositionY',
'CameraPositionZ',
'CameraRotationPitch',
'CameraRotationRoll',
'CameraRotationYaw'])
for lidar in self._lidars:
add_section(S_CAPTURE + '/' + lidar.LidarName, lidar, [
'Channels',
'Range',
'PointsPerSecond',
'RotationFrequency',
'UpperFovLimit',
'LowerFovLimit',
'ShowDebugPoints',
'LidarPositionX',
'LidarPositionY',
'LidarPositionZ',
'LidarRotationPitch',
'LidarRotationRoll',
'LidarRotationYaw'])
if sys.version_info >= (3, 0): if sys.version_info >= (3, 0):
text = io.StringIO() text = io.StringIO()
@ -140,29 +113,3 @@ class CarlaSettings(object):
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):
# pylint: disable=protected-access
return [camera.CameraName for camera in settings._cameras] + \
[lidar.LidarName for lidar in settings._lidars]
ini = ConfigParser()
if sys.version_info >= (3, 2):
ini.read_string(settings)
elif sys.version_info >= (3, 0):
ini.readfp(io.StringIO(settings)) # pylint: disable=deprecated-method
else:
ini.readfp(io.BytesIO(settings)) # pylint: disable=deprecated-method
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

@ -22,7 +22,7 @@ from carla.tcp import TCPConnectionError
from carla.util import print_over_same_line from carla.util import print_over_same_line
def run_carla_client(host, port, autopilot_on, save_images_to_disk, image_filename_format, lidar_filename_format, settings_filepath): def run_carla_client(args):
# Here we will run 3 episodes with 300 frames each. # Here we will run 3 episodes with 300 frames each.
number_of_episodes = 3 number_of_episodes = 3
frames_per_episode = 300 frames_per_episode = 300
@ -32,13 +32,13 @@ def run_carla_client(host, port, autopilot_on, save_images_to_disk, image_filena
# context manager, it creates a CARLA client object and starts the # context manager, it creates a CARLA client object and starts the
# connection. It will throw an exception if something goes wrong. The # connection. It will throw an exception if something goes wrong. The
# context manager makes sure the connection is always cleaned up on exit. # context manager makes sure the connection is always cleaned up on exit.
with make_carla_client(host, port) as client: with make_carla_client(args.host, args.port) as client:
print('CarlaClient connected') print('CarlaClient connected')
for episode in range(0, number_of_episodes): for episode in range(0, number_of_episodes):
# Start a new episode. # Start a new episode.
if settings_filepath is None: if args.settings_filepath is None:
# Create a CarlaSettings object. This object is a wrapper around # Create a CarlaSettings object. This object is a wrapper around
# the CarlaSettings.ini file. Here we set the configuration we # the CarlaSettings.ini file. Here we set the configuration we
@ -70,23 +70,23 @@ def run_carla_client(host, port, autopilot_on, save_images_to_disk, image_filena
camera1.set_position(30, 0, 130) camera1.set_position(30, 0, 130)
settings.add_sensor(camera1) settings.add_sensor(camera1)
lidar0 = Lidar('Lidar32') if args.lidar:
lidar0.set_position(0, 0, 250) lidar = Lidar('Lidar32')
lidar0.set_rotation(0, 0, 0) lidar.set_position(0, 0, 250)
lidar0.set( lidar.set_rotation(0, 0, 0)
lidar.set(
Channels=32, Channels=32,
Range=5000, Range=5000,
PointsPerSecond=100000, PointsPerSecond=100000,
RotationFrequency=10, RotationFrequency=10,
UpperFovLimit=10, UpperFovLimit=10,
LowerFovLimit = -30, LowerFovLimit=-30)
ShowDebugPoints = False) settings.add_sensor(lidar)
settings.add_sensor(lidar0)
else: else:
# Alternatively, we can load these settings from a file. # Alternatively, we can load these settings from a file.
with open(settings_filepath, 'r') as fp: with open(args.settings_filepath, 'r') as fp:
settings = fp.read() settings = fp.read()
# Now we load these settings into the server. The server replies # Now we load these settings into the server. The server replies
@ -115,12 +115,13 @@ def run_carla_client(host, port, autopilot_on, save_images_to_disk, image_filena
print_measurements(measurements) print_measurements(measurements)
# Save the images to disk if requested. # Save the images to disk if requested.
if save_images_to_disk: if args.save_images_to_disk:
for name, measurement in sensor_data.items(): for name, measurement in sensor_data.items():
if isinstance(measurement, LidarMeasurement): if isinstance(measurement, LidarMeasurement):
measurement.save_to_disk(lidar_filename_format.format(episode, name, frame)) filename = args.lidar_filename_format
else: else:
measurement.save_to_disk(image_filename_format.format(episode, name, frame)) filename = args.image_filename_format
measurement.save_to_disk(filename.format(episode, name, frame))
# We can access the encoded data of a given image as numpy # We can access the encoded data of a given image as numpy
# array using its "data" property. For instance, to get the # array using its "data" property. For instance, to get the
@ -134,7 +135,7 @@ def run_carla_client(host, port, autopilot_on, save_images_to_disk, image_filena
# If we are in synchronous mode the server will pause the # If we are in synchronous mode the server will pause the
# simulation until we send this control. # simulation until we send this control.
if not autopilot_on: if not args.autopilot:
client.send_control( client.send_control(
steer=random.uniform(-1.0, 1.0), steer=random.uniform(-1.0, 1.0),
@ -199,13 +200,19 @@ def main():
'-a', '--autopilot', '-a', '--autopilot',
action='store_true', action='store_true',
help='enable autopilot') help='enable autopilot')
argparser.add_argument(
'-l', '--lidar',
action='store_true',
help='enable Lidar')
argparser.add_argument( argparser.add_argument(
'-i', '--images-to-disk', '-i', '--images-to-disk',
action='store_true', action='store_true',
help='save images to disk') dest='save_images_to_disk',
help='save images (and Lidar data if active) to disk')
argparser.add_argument( argparser.add_argument(
'-c', '--carla-settings', '-c', '--carla-settings',
metavar='PATH', metavar='PATH',
dest='settings_filepath',
default=None, default=None,
help='Path to a "CarlaSettings.ini" file') help='Path to a "CarlaSettings.ini" file')
@ -216,17 +223,13 @@ def main():
logging.info('listening to server %s:%s', args.host, args.port) logging.info('listening to server %s:%s', args.host, args.port)
args.image_filename_format = '_out/episode_{:0>4d}/{:s}/{:0>6d}.png'
args.lidar_filename_format = '_out/episode_{:0>4d}/{:s}/{:0>6d}.ply'
while True: while True:
try: try:
run_carla_client( run_carla_client(args)
host=args.host,
port=args.port,
autopilot_on=args.autopilot,
save_images_to_disk=args.images_to_disk,
image_filename_format='_out/episode_{:0>4d}/{:s}/{:0>6d}.png',
lidar_filename_format='_out/episode_{:0>4d}/{:s}/{:0>6d}.json',
settings_filepath=args.carla_settings)
print('Done.') print('Done.')
return return

View File

@ -68,7 +68,7 @@ MINI_WINDOW_WIDTH = 320
MINI_WINDOW_HEIGHT = 180 MINI_WINDOW_HEIGHT = 180
def make_carla_settings(): def make_carla_settings(enable_lidar):
"""Make a CarlaSettings object with the settings we need.""" """Make a CarlaSettings object with the settings we need."""
settings = CarlaSettings() settings = CarlaSettings()
settings.set( settings.set(
@ -93,19 +93,18 @@ def make_carla_settings():
camera2.set_position(200, 0, 140) camera2.set_position(200, 0, 140)
camera2.set_rotation(0.0, 0.0, 0.0) camera2.set_rotation(0.0, 0.0, 0.0)
settings.add_sensor(camera2) settings.add_sensor(camera2)
lidar0 = sensor.Lidar('Lidar32') if enable_lidar:
lidar0.set_position(0, 0, 250) lidar = sensor.Lidar('Lidar32')
lidar0.set_rotation(0, 0, 0) lidar.set_position(0, 0, 250)
lidar0.set( lidar.set_rotation(0, 0, 0)
lidar.set(
Channels=32, Channels=32,
Range=5000, Range=5000,
PointsPerSecond=100000, PointsPerSecond=100000,
RotationFrequency=10, RotationFrequency=10,
UpperFovLimit=10, UpperFovLimit=10,
LowerFovLimit = -30, LowerFovLimit=-30)
ShowDebugPoints = False) settings.add_sensor(lidar)
settings.add_sensor(lidar0)
return settings return settings
@ -130,13 +129,14 @@ class Timer(object):
class CarlaGame(object): class CarlaGame(object):
def __init__(self, carla_client, city_name=None): def __init__(self, carla_client, enable_lidar=False, city_name=None):
self.client = carla_client self.client = carla_client
self._timer = None self._timer = None
self._display = None self._display = None
self._main_image = None self._main_image = None
self._mini_view_image1 = None self._mini_view_image1 = None
self._mini_view_image2 = None self._mini_view_image2 = None
self._enable_lidar = enable_lidar
self._lidar_measurement = None self._lidar_measurement = None
self._map_view = None self._map_view = None
self._is_on_reverse = False self._is_on_reverse = False
@ -175,7 +175,7 @@ class CarlaGame(object):
self._on_new_episode() self._on_new_episode()
def _on_new_episode(self): def _on_new_episode(self):
scene = self.client.load_settings(make_carla_settings()) scene = self.client.load_settings(make_carla_settings(self._enable_lidar))
number_of_player_starts = len(scene.player_start_spots) number_of_player_starts = len(scene.player_start_spots)
player_start = np.random.randint(number_of_player_starts) player_start = np.random.randint(number_of_player_starts)
print('Starting new episode...') print('Starting new episode...')
@ -191,6 +191,7 @@ class CarlaGame(object):
self._main_image = sensor_data['CameraRGB'] self._main_image = sensor_data['CameraRGB']
self._mini_view_image1 = sensor_data['CameraDepth'] self._mini_view_image1 = sensor_data['CameraDepth']
self._mini_view_image2 = sensor_data['CameraSemSeg'] self._mini_view_image2 = sensor_data['CameraSemSeg']
if self._enable_lidar:
self._lidar_measurement = sensor_data['Lidar32'] self._lidar_measurement = sensor_data['Lidar32']
# Print measurements every second. # Print measurements every second.
@ -261,7 +262,8 @@ class CarlaGame(object):
map_position, map_position,
lane_orientation): lane_orientation):
message = 'Step {step} ({fps:.1f} FPS): ' message = 'Step {step} ({fps:.1f} FPS): '
message += 'Map Position ({map_x:.1f},{map_y:.1f}) Lane Orientation ({ori_x:.1f},{ori_y:.1f}) ' message += 'Map Position ({map_x:.1f},{map_y:.1f}) '
message += 'Lane Orientation ({ori_x:.1f},{ori_y:.1f}) '
message += '{speed:.2f} km/h, ' message += '{speed:.2f} km/h, '
message += '{other_lane:.0f}% other lane, {offroad:.0f}% off-road' message += '{other_lane:.0f}% other lane, {offroad:.0f}% off-road'
message = message.format( message = message.format(
@ -311,8 +313,7 @@ class CarlaGame(object):
surface, (2 * gap_x + MINI_WINDOW_WIDTH, mini_image_y)) surface, (2 * gap_x + MINI_WINDOW_WIDTH, mini_image_y))
if self._lidar_measurement is not None: if self._lidar_measurement is not None:
lidar_data = np.array(self._lidar_measurement.data[:, :2])
lidar_data = np.array(self._lidar_measurement.data['points'][:, :, :2])
lidar_data /= 50.0 lidar_data /= 50.0
lidar_data += 100.0 lidar_data += 100.0
lidar_data = np.fabs(lidar_data) lidar_data = np.fabs(lidar_data)
@ -322,16 +323,16 @@ class CarlaGame(object):
lidar_img_size = (200, 200, 3) lidar_img_size = (200, 200, 3)
lidar_img = np.zeros(lidar_img_size) lidar_img = np.zeros(lidar_img_size)
lidar_img[tuple(lidar_data.T)] = (255, 255, 255) lidar_img[tuple(lidar_data.T)] = (255, 255, 255)
surface = pygame.surfarray.make_surface( surface = pygame.surfarray.make_surface(lidar_img)
lidar_img
)
self._display.blit(surface, (10, 10)) self._display.blit(surface, (10, 10))
if self._map_view is not None: if self._map_view is not None:
array = self._map_view array = self._map_view
array = array[:, :, :3] array = array[:, :, :3]
new_window_width =(float(WINDOW_HEIGHT)/float(self._map_shape[0]))*float(self._map_shape[1]) new_window_width = \
(float(WINDOW_HEIGHT) / float(self._map_shape[0])) * \
float(self._map_shape[1])
surface = pygame.surfarray.make_surface(array.swapaxes(0, 1)) surface = pygame.surfarray.make_surface(array.swapaxes(0, 1))
w_pos = int(self._position[0]*(float(WINDOW_HEIGHT)/float(self._map_shape[0]))) w_pos = int(self._position[0]*(float(WINDOW_HEIGHT)/float(self._map_shape[0])))
@ -374,11 +375,16 @@ def main():
default=2000, default=2000,
type=int, type=int,
help='TCP port to listen to (default: 2000)') help='TCP port to listen to (default: 2000)')
argparser.add_argument(
'-l', '--lidar',
action='store_true',
help='enable Lidar')
argparser.add_argument( argparser.add_argument(
'-m', '--map-name', '-m', '--map-name',
metavar='M', metavar='M',
default=None, default=None,
help='plot the map of the current city (needs to match active map in server, options: Town01 or Town02)') help='plot the map of the current city (needs to match active map in '
'server, options: Town01 or Town02)')
args = argparser.parse_args() args = argparser.parse_args()
log_level = logging.DEBUG if args.debug else logging.INFO log_level = logging.DEBUG if args.debug else logging.INFO
@ -392,7 +398,7 @@ def main():
try: try:
with make_carla_client(args.host, args.port) as client: with make_carla_client(args.host, args.port) as client:
game = CarlaGame(client, args.map_name) game = CarlaGame(client, args.lidar, args.map_name)
game.execute() game.execute()
break break

View File

@ -51,17 +51,13 @@ def run_carla_client(host, port, far):
WeatherId=random.choice([1, 3, 7, 8, 14])) WeatherId=random.choice([1, 3, 7, 8, 14]))
settings.randomize_seeds() settings.randomize_seeds()
camera1 = Camera( camera1 = Camera('CameraDepth', PostProcessing='Depth', FOV=fov)
'CameraDepth', PostProcessing='Depth', CameraFOV=fov
)
camera1.set_image_size(*image_size) camera1.set_image_size(*image_size)
camera1.set_position(*camera_local_pos) camera1.set_position(*camera_local_pos)
camera1.set_rotation(*camera_local_rotation) camera1.set_rotation(*camera_local_rotation)
settings.add_sensor(camera1) settings.add_sensor(camera1)
camera2 = Camera( camera2 = Camera('CameraRGB', PostProcessing='SceneFinal', FOV=fov)
'CameraRGB', PostProcessing='SceneFinal', CameraFOV=fov
)
camera2.set_image_size(*image_size) camera2.set_image_size(*image_size)
camera2.set_position(*camera_local_pos) camera2.set_position(*camera_local_pos)
camera2.set_rotation(*camera_local_rotation) camera2.set_rotation(*camera_local_rotation)

View File

@ -13,6 +13,7 @@ import carla
from carla.client import CarlaClient from carla.client import CarlaClient
from carla.sensor import Camera, Image from carla.sensor import Camera, Image
from carla.sensor import Lidar, LidarMeasurement
from carla.settings import CarlaSettings from carla.settings import CarlaSettings
from carla.util import make_connection from carla.util import make_connection
@ -45,8 +46,8 @@ class _BasicTestBase(unit_tests.CarlaServerTest):
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(sensor_data) != len(carla_settings._sensors):
raise RuntimeError('received %d images, expected %d' % (len(images), len(carla_settings._cameras))) raise RuntimeError('received %d, expected %d' % (len(sensor_data), len(carla_settings._sensors)))
logging.debug('sending control...') logging.debug('sending control...')
control = measurements.player_measurements.autopilot_control control = measurements.player_measurements.autopilot_control
if not use_autopilot_control: if not use_autopilot_control:
@ -80,7 +81,7 @@ class TwoCameras(_BasicTestBase):
settings = CarlaSettings() settings = CarlaSettings()
settings.add_sensor(Camera('DefaultCamera')) settings.add_sensor(Camera('DefaultCamera'))
camera2 = Camera('Camera2') camera2 = Camera('Camera2')
camera2.set(PostProcessing='Depth', CameraFOV=120) camera2.set(PostProcessing='Depth', FOV=120)
camera2.set_image_size(1924, 1028) camera2.set_image_size(1924, 1028)
settings.add_sensor(camera2) settings.add_sensor(camera2)
self.run_carla_client(settings, 3, 100) self.run_carla_client(settings, 3, 100)
@ -110,3 +111,10 @@ class LongEpisode(_BasicTestBase):
settings = CarlaSettings() settings = CarlaSettings()
settings.add_sensor(Camera('DefaultCamera')) settings.add_sensor(Camera('DefaultCamera'))
self.run_carla_client(settings, 1, 2000, use_autopilot_control=True) self.run_carla_client(settings, 1, 2000, use_autopilot_control=True)
class LidarTest(_BasicTestBase):
def run(self):
settings = CarlaSettings()
settings.add_sensor(Lidar('DefaultLidar'))
self.run_carla_client(settings, 3, 100)

View File

@ -17,7 +17,7 @@ void UCameraDescription::Load(const FIniFile &Config, const FString &Section)
PostProcessEffect = PostProcessEffect::FromString(PostProcessing); PostProcessEffect = PostProcessEffect::FromString(PostProcessing);
Config.GetInt(*Section, TEXT("ImageSizeX"), ImageSizeX); Config.GetInt(*Section, TEXT("ImageSizeX"), ImageSizeX);
Config.GetInt(*Section, TEXT("ImageSizeY"), ImageSizeY); Config.GetInt(*Section, TEXT("ImageSizeY"), ImageSizeY);
Config.GetFloat(*Section, TEXT("CameraFOV"), FOVAngle); Config.GetFloat(*Section, TEXT("FOV"), FOVAngle);
} }
void UCameraDescription::Validate() void UCameraDescription::Validate()