Merge branch 'master' into documentation
This commit is contained in:
commit
810b84e084
|
@ -50,7 +50,7 @@ SeedPedestrians=123456789
|
|||
; Uncomment next line to add a camera called MyCamera to the vehicle
|
||||
; Sensors=MyCamera
|
||||
|
||||
; or uncomment next line to add a camera and a LiDAR
|
||||
; or uncomment next line to add a camera and a Lidar
|
||||
; Sensors=MyCamera,MyLidar
|
||||
|
||||
; or uncomment next line to add a regular camera and a depth camera
|
||||
|
@ -60,7 +60,7 @@ SeedPedestrians=123456789
|
|||
[CARLA/Sensor/MyCamera]
|
||||
; Type of the sensor. The available types are:
|
||||
; * CAMERA A scene capture camera.
|
||||
; * LIDAR_RAY_TRACE A LiDAR implementation based on ray-tracing.
|
||||
; * LIDAR_RAY_CAST A Lidar implementation based on ray-casting.
|
||||
SensorType=CAMERA
|
||||
; Post-processing effect to be applied to this camera. Valid values:
|
||||
; * None No effects applied.
|
||||
|
@ -90,7 +90,7 @@ PostProcessing=Depth
|
|||
|
||||
|
||||
[CARLA/Sensor/MyLidar]
|
||||
SensorType=LIDAR_RAY_TRACE
|
||||
SensorType=LIDAR_RAY_CAST
|
||||
; Number of lasers.
|
||||
Channels=32
|
||||
; Measure distance in meters.
|
||||
|
|
|
@ -19,7 +19,7 @@ moment there are four different sensors available.
|
|||
* [Camera: Scene final](#camera-scene-final)
|
||||
* [Camera: Depth map](#camera-depth-map)
|
||||
* [Camera: Semantic segmentation](#camera-semantic-segmentation)
|
||||
* [Ray-trace based lidar](#ray-trace-based-lidar)
|
||||
* [Ray-cast based lidar](#ray-cast-based-lidar)
|
||||
|
||||
!!! note
|
||||
The images are sent by the server as a BGRA array of bytes. The provided
|
||||
|
@ -219,12 +219,12 @@ RotationRoll=0
|
|||
RotationYaw=0
|
||||
```
|
||||
|
||||
Ray-trace based Lidar
|
||||
---------------------
|
||||
Ray-cast based Lidar
|
||||
--------------------
|
||||
|
||||
![LidarPointCloud](img/lidar_point_cloud.gif)
|
||||
|
||||
A rotating Lidar implemented with ray-tracing. The points are computed by adding
|
||||
A rotating Lidar implemented with ray-casting. The points are computed by adding
|
||||
a laser for each channel distributed in the vertical FOV, then the rotation is
|
||||
simulated computing the horizontal angle that the Lidar rotated this frame, and
|
||||
doing a ray-cast for each point that each laser was supposed to generate this
|
||||
|
@ -264,7 +264,7 @@ carla_settings.add_sensor(lidar)
|
|||
|
||||
```ini
|
||||
[CARLA/Sensor/MyLidar]
|
||||
SensorType=LIDAR_RAY_TRACE
|
||||
SensorType=LIDAR_RAY_CAST
|
||||
Channels=32
|
||||
Range=50
|
||||
PointsPerSecond=100000
|
||||
|
|
|
@ -19,7 +19,7 @@ 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\"6\n\nRotation3D\x12\r\n\x05pitch\x18\x01 \x01(\x02\x12\x0b\n\x03yaw\x18\x02 \x01(\x02\x12\x0c\n\x04roll\x18\x03 \x01(\x02\"\x92\x01\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.Vector3DB\x02\x18\x01\x12*\n\x08rotation\x18\x03 \x01(\x0b\x32\x18.carla_server.Rotation3D\"\x81\x01\n\x06Sensor\x12\n\n\x02id\x18\x01 \x01(\x07\x12\'\n\x04type\x18\x02 \x01(\x0e\x32\x19.carla_server.Sensor.Type\x12\x0c\n\x04name\x18\x03 \x01(\t\"4\n\x04Type\x12\x0b\n\x07UNKNOWN\x10\x00\x12\n\n\x06\x43\x41MERA\x10\x01\x12\x13\n\x0fLIDAR_RAY_TRACE\x10\x02\"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\"n\n\x10SceneDescription\x12\x33\n\x12player_start_spots\x18\x01 \x03(\x0b\x32\x17.carla_server.Transform\x12%\n\x07sensors\x18\x02 \x03(\x0b\x32\x14.carla_server.Sensor\"/\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\"\xb6\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\xf5\x02\n\x12PlayerMeasurements\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12*\n\nbox_extent\x18\x0b \x01(\x0b\x32\x16.carla_server.Vector3D\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')
|
||||
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\"6\n\nRotation3D\x12\r\n\x05pitch\x18\x01 \x01(\x02\x12\x0b\n\x03yaw\x18\x02 \x01(\x02\x12\x0c\n\x04roll\x18\x03 \x01(\x02\"\x92\x01\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.Vector3DB\x02\x18\x01\x12*\n\x08rotation\x18\x03 \x01(\x0b\x32\x18.carla_server.Rotation3D\"\x80\x01\n\x06Sensor\x12\n\n\x02id\x18\x01 \x01(\x07\x12\'\n\x04type\x18\x02 \x01(\x0e\x32\x19.carla_server.Sensor.Type\x12\x0c\n\x04name\x18\x03 \x01(\t\"3\n\x04Type\x12\x0b\n\x07UNKNOWN\x10\x00\x12\n\n\x06\x43\x41MERA\x10\x01\x12\x12\n\x0eLIDAR_RAY_CAST\x10\x02\"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\"n\n\x10SceneDescription\x12\x33\n\x12player_start_spots\x18\x01 \x03(\x0b\x32\x17.carla_server.Transform\x12%\n\x07sensors\x18\x02 \x03(\x0b\x32\x14.carla_server.Sensor\"/\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\"\xb6\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\xf5\x02\n\x12PlayerMeasurements\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12*\n\nbox_extent\x18\x0b \x01(\x0b\x32\x16.carla_server.Vector3D\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')
|
||||
)
|
||||
|
||||
|
||||
|
@ -39,14 +39,14 @@ _SENSOR_TYPE = _descriptor.EnumDescriptor(
|
|||
options=None,
|
||||
type=None),
|
||||
_descriptor.EnumValueDescriptor(
|
||||
name='LIDAR_RAY_TRACE', index=2, number=2,
|
||||
name='LIDAR_RAY_CAST', index=2, number=2,
|
||||
options=None,
|
||||
type=None),
|
||||
],
|
||||
containing_type=None,
|
||||
options=None,
|
||||
serialized_start=364,
|
||||
serialized_end=416,
|
||||
serialized_end=415,
|
||||
)
|
||||
_sym_db.RegisterEnumDescriptor(_SENSOR_TYPE)
|
||||
|
||||
|
@ -71,8 +71,8 @@ _TRAFFICLIGHT_STATE = _descriptor.EnumDescriptor(
|
|||
],
|
||||
containing_type=None,
|
||||
options=None,
|
||||
serialized_start=775,
|
||||
serialized_end=814,
|
||||
serialized_start=774,
|
||||
serialized_end=813,
|
||||
)
|
||||
_sym_db.RegisterEnumDescriptor(_TRAFFICLIGHT_STATE)
|
||||
|
||||
|
@ -254,7 +254,7 @@ _SENSOR = _descriptor.Descriptor(
|
|||
oneofs=[
|
||||
],
|
||||
serialized_start=287,
|
||||
serialized_end=416,
|
||||
serialized_end=415,
|
||||
)
|
||||
|
||||
|
||||
|
@ -298,8 +298,8 @@ _VEHICLE = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=418,
|
||||
serialized_end=538,
|
||||
serialized_start=417,
|
||||
serialized_end=537,
|
||||
)
|
||||
|
||||
|
||||
|
@ -343,8 +343,8 @@ _PEDESTRIAN = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=540,
|
||||
serialized_end=663,
|
||||
serialized_start=539,
|
||||
serialized_end=662,
|
||||
)
|
||||
|
||||
|
||||
|
@ -382,8 +382,8 @@ _TRAFFICLIGHT = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=666,
|
||||
serialized_end=814,
|
||||
serialized_start=665,
|
||||
serialized_end=813,
|
||||
)
|
||||
|
||||
|
||||
|
@ -420,8 +420,8 @@ _SPEEDLIMITSIGN = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=816,
|
||||
serialized_end=897,
|
||||
serialized_start=815,
|
||||
serialized_end=896,
|
||||
)
|
||||
|
||||
|
||||
|
@ -482,8 +482,8 @@ _AGENT = _descriptor.Descriptor(
|
|||
name='agent', full_name='carla_server.Agent.agent',
|
||||
index=0, containing_type=None, fields=[]),
|
||||
],
|
||||
serialized_start=900,
|
||||
serialized_end=1129,
|
||||
serialized_start=899,
|
||||
serialized_end=1128,
|
||||
)
|
||||
|
||||
|
||||
|
@ -513,8 +513,8 @@ _REQUESTNEWEPISODE = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=1131,
|
||||
serialized_end=1168,
|
||||
serialized_start=1130,
|
||||
serialized_end=1167,
|
||||
)
|
||||
|
||||
|
||||
|
@ -551,8 +551,8 @@ _SCENEDESCRIPTION = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=1170,
|
||||
serialized_end=1280,
|
||||
serialized_start=1169,
|
||||
serialized_end=1279,
|
||||
)
|
||||
|
||||
|
||||
|
@ -582,8 +582,8 @@ _EPISODESTART = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=1282,
|
||||
serialized_end=1329,
|
||||
serialized_start=1281,
|
||||
serialized_end=1328,
|
||||
)
|
||||
|
||||
|
||||
|
@ -613,8 +613,8 @@ _EPISODEREADY = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=1331,
|
||||
serialized_end=1360,
|
||||
serialized_start=1330,
|
||||
serialized_end=1359,
|
||||
)
|
||||
|
||||
|
||||
|
@ -672,8 +672,8 @@ _CONTROL = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=1362,
|
||||
serialized_end=1456,
|
||||
serialized_start=1361,
|
||||
serialized_end=1455,
|
||||
)
|
||||
|
||||
|
||||
|
@ -766,8 +766,8 @@ _MEASUREMENTS_PLAYERMEASUREMENTS = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=1652,
|
||||
serialized_end=2025,
|
||||
serialized_start=1651,
|
||||
serialized_end=2024,
|
||||
)
|
||||
|
||||
_MEASUREMENTS = _descriptor.Descriptor(
|
||||
|
@ -817,8 +817,8 @@ _MEASUREMENTS = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=1459,
|
||||
serialized_end=2025,
|
||||
serialized_start=1458,
|
||||
serialized_end=2024,
|
||||
)
|
||||
|
||||
_TRANSFORM.fields_by_name['location'].message_type = _VECTOR3D
|
||||
|
|
|
@ -220,7 +220,7 @@ def _make_sensor_parsers(sensors):
|
|||
sensor_def = SensorDefinition(s)
|
||||
if sensor_def.type == carla_protocol.Sensor.CAMERA:
|
||||
sensor_def.parse_raw_data = parse_image
|
||||
elif sensor_def.type == carla_protocol.Sensor.LIDAR_RAY_TRACE:
|
||||
elif sensor_def.type == carla_protocol.Sensor.LIDAR_RAY_CAST:
|
||||
sensor_def.parse_raw_data = parse_lidar
|
||||
else:
|
||||
logging.error('unknown sensor type %s', sensor_def.type)
|
||||
|
|
|
@ -119,9 +119,9 @@ class Lidar(Sensor):
|
|||
"""
|
||||
|
||||
def __init__(self, name, **kwargs):
|
||||
super(Lidar, self).__init__(name, sensor_type="LIDAR_RAY_TRACE")
|
||||
super(Lidar, self).__init__(name, sensor_type="LIDAR_RAY_CAST")
|
||||
self.Channels = 32
|
||||
self.Range = 5000.0
|
||||
self.Range = 50.0
|
||||
self.PointsPerSecond = 56000
|
||||
self.RotationFrequency = 10.0
|
||||
self.UpperFovLimit = 10.0
|
||||
|
|
|
@ -49,7 +49,8 @@ def run_carla_client(args):
|
|||
SendNonPlayerAgentsInfo=True,
|
||||
NumberOfVehicles=20,
|
||||
NumberOfPedestrians=40,
|
||||
WeatherId=random.choice([1, 3, 7, 8, 14]))
|
||||
WeatherId=random.choice([1, 3, 7, 8, 14]),
|
||||
QualityLevel=args.quality_level)
|
||||
settings.randomize_seeds()
|
||||
|
||||
# Now we want to add a couple of cameras to the player vehicle.
|
||||
|
@ -76,7 +77,7 @@ def run_carla_client(args):
|
|||
lidar.set_rotation(0, 0, 0)
|
||||
lidar.set(
|
||||
Channels=32,
|
||||
Range=5000,
|
||||
Range=50,
|
||||
PointsPerSecond=100000,
|
||||
RotationFrequency=10,
|
||||
UpperFovLimit=10,
|
||||
|
@ -201,6 +202,12 @@ def main():
|
|||
'-l', '--lidar',
|
||||
action='store_true',
|
||||
help='enable Lidar')
|
||||
argparser.add_argument(
|
||||
'-q', '--quality-level',
|
||||
choices=['Low', 'Epic'],
|
||||
type=lambda s: s.title(),
|
||||
default='Epic',
|
||||
help='graphics quality level, a lower level makes the simulation run considerably faster.')
|
||||
argparser.add_argument(
|
||||
'-i', '--images-to-disk',
|
||||
action='store_true',
|
||||
|
|
|
@ -70,7 +70,7 @@ MINI_WINDOW_WIDTH = 320
|
|||
MINI_WINDOW_HEIGHT = 180
|
||||
|
||||
|
||||
def make_carla_settings(enable_lidar):
|
||||
def make_carla_settings(args):
|
||||
"""Make a CarlaSettings object with the settings we need."""
|
||||
settings = CarlaSettings()
|
||||
settings.set(
|
||||
|
@ -78,7 +78,8 @@ def make_carla_settings(enable_lidar):
|
|||
SendNonPlayerAgentsInfo=True,
|
||||
NumberOfVehicles=15,
|
||||
NumberOfPedestrians=30,
|
||||
WeatherId=random.choice([1, 3, 7, 8, 14]))
|
||||
WeatherId=random.choice([1, 3, 7, 8, 14]),
|
||||
QualityLevel=args.quality_level)
|
||||
settings.randomize_seeds()
|
||||
camera0 = sensor.Camera('CameraRGB')
|
||||
camera0.set_image_size(WINDOW_WIDTH, WINDOW_HEIGHT)
|
||||
|
@ -95,7 +96,7 @@ def make_carla_settings(enable_lidar):
|
|||
camera2.set_position(2.0, 0.0, 1.4)
|
||||
camera2.set_rotation(0.0, 0.0, 0.0)
|
||||
settings.add_sensor(camera2)
|
||||
if enable_lidar:
|
||||
if args.lidar:
|
||||
lidar = sensor.Lidar('Lidar32')
|
||||
lidar.set_position(0, 0, 2.5)
|
||||
lidar.set_rotation(0, 0, 0)
|
||||
|
@ -131,22 +132,22 @@ class Timer(object):
|
|||
|
||||
|
||||
class CarlaGame(object):
|
||||
def __init__(self, carla_client, enable_autopilot=False, enable_lidar=False, city_name=None):
|
||||
def __init__(self, carla_client, args):
|
||||
self.client = carla_client
|
||||
self._carla_settings = make_carla_settings(args)
|
||||
self._timer = None
|
||||
self._display = None
|
||||
self._main_image = None
|
||||
self._mini_view_image1 = None
|
||||
self._mini_view_image2 = None
|
||||
self._enable_autopilot = enable_autopilot
|
||||
self._enable_lidar = enable_lidar
|
||||
self._enable_autopilot = args.autopilot
|
||||
self._lidar_measurement = None
|
||||
self._map_view = None
|
||||
self._is_on_reverse = False
|
||||
self._city_name = city_name
|
||||
self._map = CarlaMap(city_name, 16.43, 50.0) if city_name is not None else None
|
||||
self._map_shape = self._map.map_image.shape if city_name is not None else None
|
||||
self._map_view = self._map.get_map(WINDOW_HEIGHT) if city_name is not None else None
|
||||
self._city_name = args.map_name
|
||||
self._map = CarlaMap(self._city_name, 16.43, 50.0) if self._city_name is not None else None
|
||||
self._map_shape = self._map.map_image.shape if self._city_name is not None else None
|
||||
self._map_view = self._map.get_map(WINDOW_HEIGHT) if self._city_name is not None else None
|
||||
self._position = None
|
||||
self._agent_positions = None
|
||||
|
||||
|
@ -178,7 +179,7 @@ class CarlaGame(object):
|
|||
self._on_new_episode()
|
||||
|
||||
def _on_new_episode(self):
|
||||
scene = self.client.load_settings(make_carla_settings(self._enable_lidar))
|
||||
scene = self.client.load_settings(self._carla_settings)
|
||||
number_of_player_starts = len(scene.player_start_spots)
|
||||
player_start = np.random.randint(number_of_player_starts)
|
||||
print('Starting new episode...')
|
||||
|
@ -191,11 +192,10 @@ class CarlaGame(object):
|
|||
|
||||
measurements, sensor_data = self.client.read_data()
|
||||
|
||||
self._main_image = sensor_data.get('CameraRGB',None)
|
||||
self._mini_view_image1 = sensor_data.get('CameraDepth' ,None)
|
||||
self._mini_view_image2 = sensor_data.get('CameraSemSeg',None)
|
||||
if self._enable_lidar:
|
||||
self._lidar_measurement = sensor_data.get('Lidar32',None)
|
||||
self._main_image = sensor_data.get('CameraRGB', None)
|
||||
self._mini_view_image1 = sensor_data.get('CameraDepth', None)
|
||||
self._mini_view_image2 = sensor_data.get('CameraSemSeg', None)
|
||||
self._lidar_measurement = sensor_data.get('Lidar32', None)
|
||||
|
||||
# Print measurements every second.
|
||||
if self._timer.elapsed_seconds_since_lap() > 1.0:
|
||||
|
@ -321,7 +321,7 @@ class CarlaGame(object):
|
|||
|
||||
if self._lidar_measurement is not None:
|
||||
lidar_data = np.array(self._lidar_measurement.data[:, :2])
|
||||
lidar_data /= 50.0
|
||||
lidar_data *= 2.0
|
||||
lidar_data += 100.0
|
||||
lidar_data = np.fabs(lidar_data)
|
||||
lidar_data = lidar_data.astype(np.int32)
|
||||
|
@ -390,6 +390,12 @@ def main():
|
|||
'-l', '--lidar',
|
||||
action='store_true',
|
||||
help='enable Lidar')
|
||||
argparser.add_argument(
|
||||
'-q', '--quality-level',
|
||||
choices=['Low', 'Epic'],
|
||||
type=lambda s: s.title(),
|
||||
default='Epic',
|
||||
help='graphics quality level, a lower level makes the simulation run considerably faster.')
|
||||
argparser.add_argument(
|
||||
'-m', '--map-name',
|
||||
metavar='M',
|
||||
|
@ -409,7 +415,7 @@ def main():
|
|||
try:
|
||||
|
||||
with make_carla_client(args.host, args.port) as client:
|
||||
game = CarlaGame(client, args.autopilot, args.lidar, args.map_name)
|
||||
game = CarlaGame(client, args)
|
||||
game.execute()
|
||||
break
|
||||
|
||||
|
|
|
@ -46,52 +46,74 @@ def make_base_settings():
|
|||
SeedPedestrians=123456789,
|
||||
QualityLevel='Epic')
|
||||
|
||||
|
||||
def generate_settings_scenario_001():
|
||||
logging.info('Scenario 001: no sensors, no agents info')
|
||||
logging.info('Scenario 001: no sensors')
|
||||
return make_base_settings()
|
||||
|
||||
|
||||
def generate_settings_scenario_002():
|
||||
logging.info('Scenario 002: no sensors, sending agents info')
|
||||
logging.info('Scenario 002: no sensors, no agents at all')
|
||||
settings = make_base_settings()
|
||||
settings.set(NumberOfVehicles=0, NumberOfPedestrians=0)
|
||||
return settings
|
||||
|
||||
|
||||
def generate_settings_scenario_003():
|
||||
logging.info('Scenario 003: no sensors, no pedestrians')
|
||||
settings = make_base_settings()
|
||||
settings.set(NumberOfPedestrians=0)
|
||||
return settings
|
||||
|
||||
|
||||
def generate_settings_scenario_004():
|
||||
logging.info('Scenario 004: no sensors, no vehicles')
|
||||
settings = make_base_settings()
|
||||
settings.set(NumberOfVehicles=0)
|
||||
return settings
|
||||
|
||||
|
||||
def generate_settings_scenario_005():
|
||||
logging.info('Scenario 005: no sensors, hard rain')
|
||||
settings = make_base_settings()
|
||||
settings.set(WeatherId=13)
|
||||
return settings
|
||||
|
||||
|
||||
def generate_settings_scenario_006():
|
||||
logging.info('Scenario 006: no sensors, sending agents info')
|
||||
settings = make_base_settings()
|
||||
settings.set(SendNonPlayerAgentsInfo=True)
|
||||
return settings
|
||||
|
||||
|
||||
def generate_settings_scenario_003():
|
||||
logging.info('Scenario 003: single camera RGB, no agents info')
|
||||
def generate_settings_scenario_007():
|
||||
logging.info('Scenario 007: single camera RGB')
|
||||
settings = make_base_settings()
|
||||
settings.add_sensor(Camera('DefaultCamera'))
|
||||
settings.add_sensor(Camera('DefaultRGBCamera'))
|
||||
return settings
|
||||
|
||||
|
||||
def generate_settings_scenario_004():
|
||||
logging.info('Scenario 004: single camera Depth, no agents info')
|
||||
def generate_settings_scenario_008():
|
||||
logging.info('Scenario 008: single camera Depth')
|
||||
settings = make_base_settings()
|
||||
settings.add_sensor(Camera('DefaultCamera', PostProcessing='Depth'))
|
||||
return settings
|
||||
|
||||
|
||||
def generate_settings_scenario_005():
|
||||
logging.info('Scenario 005: single camera SemanticSegmentation, no agents info')
|
||||
settings = make_base_settings()
|
||||
settings.add_sensor(Camera('DefaultCamera', PostProcessing='SemanticSegmentation'))
|
||||
return settings
|
||||
|
||||
|
||||
def generate_settings_scenario_006():
|
||||
logging.info('Scenario 006: 3 cameras, no agents info')
|
||||
settings = make_base_settings()
|
||||
settings.add_sensor(Camera('DefaultCamera'))
|
||||
settings.add_sensor(Camera('DefaultDepthCamera', PostProcessing='Depth'))
|
||||
return settings
|
||||
|
||||
|
||||
def generate_settings_scenario_009():
|
||||
logging.info('Scenario 009: single camera SemanticSegmentation')
|
||||
settings = make_base_settings()
|
||||
settings.add_sensor(Camera('DefaultSemSegCamera', PostProcessing='SemanticSegmentation'))
|
||||
return settings
|
||||
|
||||
|
||||
def generate_settings_scenario_007():
|
||||
logging.info('Scenario 007: no sensors, no agents info, rainy')
|
||||
def generate_settings_scenario_010():
|
||||
logging.info('Scenario 010: 3 cameras')
|
||||
settings = make_base_settings()
|
||||
settings.set(WeatherId=13)
|
||||
settings.add_sensor(Camera('DefaultRGBCamera'))
|
||||
settings.add_sensor(Camera('DefaultDepthCamera', PostProcessing='Depth'))
|
||||
settings.add_sensor(Camera('DefaultSemSegCamera', PostProcessing='SemanticSegmentation'))
|
||||
return settings
|
||||
|
||||
|
||||
|
|
|
@ -38,10 +38,10 @@ Roadmap
|
|||
We are continuously working on improving CARLA, and we appreciate contributions
|
||||
from the community. Our most immediate goals are:
|
||||
|
||||
- Releasing the methods evaluated in the CARLA paper
|
||||
- Adding a LiDAR sensor
|
||||
- Allowing for flexible and user-friendly import and editing of maps
|
||||
- Allowing the users to control non-player characters (and therefore set up user-specified scenarios)
|
||||
- [ ] Releasing the methods evaluated in the CARLA paper
|
||||
- [x] Adding a Lidar sensor
|
||||
- [ ] Allowing for flexible and user-friendly import and editing of maps
|
||||
- [ ] Allowing the users to control non-player characters (and therefore set up user-specified scenarios)
|
||||
|
||||
We will post a detailed roadmap and contribution guidelines soon - stay tuned!
|
||||
|
||||
|
|
|
@ -199,6 +199,15 @@ void ACarlaGameModeBase::BeginPlay()
|
|||
GameController->BeginPlay();
|
||||
}
|
||||
|
||||
void ACarlaGameModeBase::EndPlay(const EEndPlayReason::Type EndPlayReason)
|
||||
{
|
||||
Super::EndPlay(EndPlayReason);
|
||||
if(CarlaSettingsDelegate!=nullptr && EndPlayReason==EEndPlayReason::EndPlayInEditor)
|
||||
{
|
||||
CarlaSettingsDelegate->Reset();
|
||||
}
|
||||
}
|
||||
|
||||
void ACarlaGameModeBase::Tick(float DeltaSeconds)
|
||||
{
|
||||
Super::Tick(DeltaSeconds);
|
||||
|
|
|
@ -38,6 +38,8 @@ public:
|
|||
|
||||
virtual void BeginPlay() override;
|
||||
|
||||
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
|
||||
|
||||
virtual void Tick(float DeltaSeconds) override;
|
||||
|
||||
FDataRouter &GetDataRouter()
|
||||
|
|
|
@ -60,7 +60,17 @@ void ALidar::ReadPoints(const float DeltaTime)
|
|||
const uint32 PointsToScanWithOneLaser =
|
||||
FMath::RoundHalfFromZero(
|
||||
Description->PointsPerSecond * DeltaTime / float(ChannelCount));
|
||||
check(PointsToScanWithOneLaser > 0);
|
||||
|
||||
if (PointsToScanWithOneLaser <= 0)
|
||||
{
|
||||
UE_LOG(
|
||||
LogCarla,
|
||||
Warning,
|
||||
TEXT("%s: no points requested this frame, try increasing the number of points per second."),
|
||||
*GetName());
|
||||
return;
|
||||
}
|
||||
|
||||
check(ChannelCount == LaserAngles.Num());
|
||||
check(Description != nullptr);
|
||||
|
||||
|
|
|
@ -36,7 +36,7 @@ private:
|
|||
/// Shoot a laser ray-trace, return whether the laser hit something.
|
||||
bool ShootLaser(uint32 Channel, float HorizontalAngle, FVector &Point) const;
|
||||
|
||||
UPROPERTY(Category = "LiDAR", VisibleAnywhere)
|
||||
UPROPERTY(Category = "Lidar", VisibleAnywhere)
|
||||
const ULidarDescription *Description;
|
||||
|
||||
TArray<float> LaserAngles;
|
||||
|
|
|
@ -75,9 +75,10 @@ public:
|
|||
{
|
||||
check(Header[1] > Channel);
|
||||
Header[2u + Channel] += 1u;
|
||||
Points.Emplace(Point.X);
|
||||
Points.Emplace(Point.Y);
|
||||
Points.Emplace(Point.Z);
|
||||
constexpr float TO_METERS = 1e-2f;
|
||||
Points.Emplace(TO_METERS * Point.X);
|
||||
Points.Emplace(TO_METERS * Point.Y);
|
||||
Points.Emplace(TO_METERS * Point.Z);
|
||||
}
|
||||
|
||||
FSensorDataView GetView() const
|
||||
|
|
|
@ -54,7 +54,7 @@ void FSensorFactory::Visit(const ULidarDescription &Description)
|
|||
UE_LOG(
|
||||
LogCarla,
|
||||
Log,
|
||||
TEXT("Created LiDAR %d"),
|
||||
TEXT("Created Lidar %d"),
|
||||
Lidar->GetId());
|
||||
Sensor = Lidar;
|
||||
}
|
||||
|
|
|
@ -63,7 +63,7 @@ static TUniquePtr<const char[]> Encode(
|
|||
Data.type = [](const FString &Type) {
|
||||
#define CARLA_CHECK_TYPE(Str) if (Type == TEXT(#Str)) return CARLA_SERVER_ ## Str;
|
||||
CARLA_CHECK_TYPE(CAMERA)
|
||||
CARLA_CHECK_TYPE(LIDAR_RAY_TRACE)
|
||||
CARLA_CHECK_TYPE(LIDAR_RAY_CAST)
|
||||
else return CARLA_SERVER_SENSOR_UNKNOWN;
|
||||
#undef CARLA_CHECK_TYPE
|
||||
}(SensorDescription.Type);
|
||||
|
|
|
@ -21,7 +21,6 @@
|
|||
#include "Engine/PostProcessVolume.h"
|
||||
#include "Materials/MaterialInstance.h"
|
||||
|
||||
|
||||
// INI file sections.
|
||||
#define S_CARLA_SERVER TEXT("CARLA/Server")
|
||||
#define S_CARLA_LEVELSETTINGS TEXT("CARLA/LevelSettings")
|
||||
|
@ -31,6 +30,7 @@
|
|||
// =============================================================================
|
||||
// -- Static variables & constants ---------------------------------------------
|
||||
// =============================================================================
|
||||
|
||||
const FName UCarlaSettings::CARLA_ROAD_TAG = FName("CARLA_ROAD");
|
||||
const FName UCarlaSettings::CARLA_SKY_TAG = FName("CARLA_SKY");
|
||||
|
||||
|
@ -90,7 +90,7 @@ static USensorDescription *MakeSensor(
|
|||
const auto SensorType = GetSensorType(ConfigFile, SensorName);
|
||||
if (SensorType == TEXT("CAMERA")) {
|
||||
return MakeSensor<UCameraDescription>(Parent, SensorName, SensorType);
|
||||
} else if (SensorType == TEXT("LIDAR_RAY_TRACE")) {
|
||||
} else if (SensorType == TEXT("LIDAR_RAY_CAST")) {
|
||||
return MakeSensor<ULidarDescription>(Parent, SensorName, SensorType);
|
||||
} else {
|
||||
UE_LOG(LogCarla, Error, TEXT("Invalid sensor type '%s'"), *SensorType);
|
||||
|
@ -125,8 +125,7 @@ static void LoadSettingsFromConfig(
|
|||
if(!Settings.SetQualitySettingsLevel(UQualitySettings::FromString(sQualityLevel)))
|
||||
{
|
||||
//error
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// Sensors.
|
||||
FString Sensors;
|
||||
|
@ -190,7 +189,6 @@ bool UCarlaSettings::SetQualitySettingsLevel(EQualitySettingsLevel newQualityLev
|
|||
return true;
|
||||
}
|
||||
|
||||
|
||||
void UCarlaSettings::LoadSettings()
|
||||
{
|
||||
CurrentFileName = TEXT("");
|
||||
|
@ -275,7 +273,7 @@ void UCarlaSettings::LogSettings() const
|
|||
UE_LOG(LogCarla, Log, TEXT("[%s]"), S_CARLA_SENSOR);
|
||||
UE_LOG(LogCarla, Log, TEXT("Added %d sensors."), SensorDescriptions.Num());
|
||||
UE_LOG(LogCarla, Log, TEXT("Semantic Segmentation = %s"), EnabledDisabled(bSemanticSegmentationEnabled));
|
||||
for (auto &&Sensor : SensorDescriptions)
|
||||
for (auto &&Sensor : SensorDescriptions)
|
||||
{
|
||||
check(Sensor.Value != nullptr);
|
||||
Sensor.Value->Log();
|
||||
|
|
|
@ -11,11 +11,20 @@
|
|||
#include "Engine/PostProcessVolume.h"
|
||||
#include "UObjectIterator.h"
|
||||
|
||||
///quality settings configuration between runs
|
||||
EQualitySettingsLevel UCarlaSettingsDelegate::AppliedLowPostResetQualitySettingsLevel = EQualitySettingsLevel::Epic;
|
||||
|
||||
UCarlaSettingsDelegate::UCarlaSettingsDelegate() :
|
||||
ActorSpawnedDelegate(FOnActorSpawned::FDelegate::CreateUObject(this, &UCarlaSettingsDelegate::OnActorSpawned))
|
||||
{
|
||||
}
|
||||
|
||||
void UCarlaSettingsDelegate::Reset()
|
||||
{
|
||||
LaunchEpicQualityCommands(GetLocalWorld());
|
||||
AppliedLowPostResetQualitySettingsLevel = EQualitySettingsLevel::Epic;
|
||||
}
|
||||
|
||||
void UCarlaSettingsDelegate::RegisterSpawnHandler(UWorld *InWorld)
|
||||
{
|
||||
CheckCarlaSettings(InWorld);
|
||||
|
|
|
@ -21,6 +21,9 @@ public:
|
|||
/** Constructor */
|
||||
UCarlaSettingsDelegate();
|
||||
|
||||
/** Reset settings to default */
|
||||
void Reset();
|
||||
|
||||
/** Create the event trigger handler for all new spawned actors to be processed with a custom function here */
|
||||
void RegisterSpawnHandler(UWorld *World);
|
||||
|
||||
|
@ -65,7 +68,7 @@ private:
|
|||
private:
|
||||
|
||||
/** currently applied settings level after level is restarted */
|
||||
EQualitySettingsLevel AppliedLowPostResetQualitySettingsLevel = EQualitySettingsLevel::Epic;
|
||||
static EQualitySettingsLevel AppliedLowPostResetQualitySettingsLevel;
|
||||
|
||||
/** */
|
||||
UCarlaSettings* CarlaSettings = nullptr;
|
||||
|
|
|
@ -90,7 +90,7 @@ void AVehicleSpawnerBase::SetNumberOfVehicles(const int32 Count)
|
|||
void AVehicleSpawnerBase::TryToSpawnRandomVehicle()
|
||||
{
|
||||
auto SpawnPoint = GetRandomSpawnPoint();
|
||||
if ((SpawnPoint != nullptr)) {
|
||||
if (SpawnPoint != nullptr) {
|
||||
SpawnVehicleAtSpawnPoint(*SpawnPoint);
|
||||
} else {
|
||||
UE_LOG(LogCarla, Error, TEXT("Unable to find spawn point"));
|
||||
|
|
|
@ -76,7 +76,7 @@ extern "C" {
|
|||
|
||||
#define CARLA_SERVER_SENSOR_UNKNOWN 0u
|
||||
#define CARLA_SERVER_CAMERA 101u
|
||||
#define CARLA_SERVER_LIDAR_RAY_TRACE 102u
|
||||
#define CARLA_SERVER_LIDAR_RAY_CAST 102u
|
||||
|
||||
struct carla_sensor_definition {
|
||||
/** Id of the sensor. */
|
||||
|
|
|
@ -61,7 +61,7 @@ namespace server {
|
|||
lhs->set_type([&](){
|
||||
switch (rhs.type) {
|
||||
case CARLA_SERVER_CAMERA: return cs::Sensor::CAMERA;
|
||||
case CARLA_SERVER_LIDAR_RAY_TRACE: return cs::Sensor::LIDAR_RAY_TRACE;
|
||||
case CARLA_SERVER_LIDAR_RAY_CAST: return cs::Sensor::LIDAR_RAY_CAST;
|
||||
default: return cs::Sensor::UNKNOWN;
|
||||
}
|
||||
}());
|
||||
|
|
|
@ -40,7 +40,7 @@ message Sensor {
|
|||
enum Type {
|
||||
UNKNOWN = 0;
|
||||
CAMERA = 1;
|
||||
LIDAR_RAY_TRACE = 2;
|
||||
LIDAR_RAY_CAST = 2;
|
||||
}
|
||||
|
||||
fixed32 id = 1;
|
||||
|
|
Loading…
Reference in New Issue