CARLA 0.9.4 release

Synchronous mode, dynamic map loading, logging and more!

Posted by @marcgpuig, @germanros on March 01, 2019

We are proud to announce the new features included in CARLA 0.9.4!

Get CARLA 0.9.4

This release comes with a list of very useful features to improve the simulation experience. Let’s dive into the highlights of this release!

API to control the physics engine

We added a long time requested feature to allow users to change physics properties of vehicles and their components in runtime. So if you need to adjust properties like the vehicle’s maximum revolutions per minute, steering curve or even disable wheel’s steering and more, from now on you will be able to do it! Please, check the following examples:

carla.WheelsPhysicsControl:
  tire_friction
  damping_rate
  steer_angle
  disable_steering

Code example 1: Adjustable attributes associated with wheels’ physics.

carla.VehiclePhysicsControl:
  torque_curve
  max_rpm
  moi
  damping_rate_full_throttle
  damping_rate_zero_throttle_clutch_engaged
  damping_rate_zero_throttle_clutch_disengaged
  use_gear_autobox
  gear_switch_time
  clutch_strength
  mass
  drag_coefficient
  center_of_mass
  steering_curve
  wheels

Code example 2: Adjustable attributes associated with vehicle’s physics.

phys_control = vehicle.get_physics_control()
phys_control.max_rpm = 5000
vehicle.apply_physics_control(phys_control)

Code example 3: How to modify a parameter using the new API calls.

Logging, playback and events query system

In this release, we bring you an exciting logging and playback system! This feature enables you to log all the states of a simulation session and re-run it later, under the same or different circumstances. This means you can actually deviate from an event that occurred during the original session and try alternative things. Of course, you can also use this functionality to simply play a log back. Log files are automatically stored by the server. This feature includes a camera-following mode that lets you follow a target actor while replaying the simulation, so you can replay situations from different viewpoints. Give it a try by running the new version of the manual_control.py script, with the following options:

- `CTRL + R`: Toggle recording (file is always 'manual_recording.rec')
- `CTRL + P`: Replay the last recording.
- `CTRL + -`: Subtract 1 second the start time of the replayer.
- `CTRL + =`: Add 1 second the start time of the replayer.
- `CTRL + SHIFT + -`: Subtract 10 seconds the start time of the replayer.
- `CTRL + SHIFT + =`: Add 10 seconds the start time of the replayer.
- Note: A negative time start means to replay from the end of the recording (-2 = replay the last 2 seconds)

The logging system is complemented by our new query engine. This new functionality allows users to query for different types of events present in a log file. For instance, did a vehicle collided against any other… vehicle, pedestrian, cyclist, etc.? The engine will return all the timestamps and information associated to that particular event and the playback system can be then used to resume simulation around interesting traffic situations. This gives you the right tool to focus your time on finding why your agent crashes against that car.

Major core API improvements

Synchronous mode

Synchronous mode is back! When synchronous mode is enabled, the simulator waits for updates until a client gives the order to continue. This mode can be enabled at any time via world settings (see below). Once enabled, the client is responsible for calling the tick() function.

settings = world.get_settings()
settings.synchronous_mode = True
world.apply_settings(settings)

while True:
    # Advance to next tick.
    client.tick()
    # ...

Code example 4: Setting synchronous mode and sending clock ticks.

In order to add this feature, we enforce a strict “tick order” to all the relevant CARLA actors. Things occur in the following order:

  • Send world tick (transforms, velocities, etc.) used by wait_for_tick
  • Update UE4 actors (autopilot, traffic lights, etc.)
  • Parse client requests
  • If sync-mode and client did not tick, repeat 3.

Changing maps at runtime

The following API functions allow users to change maps in runtime from client side: get_available_maps() and load_map(). get_available_maps retrieves a list containing the paths of all available maps (it dynamically finds all the maps available at runtime). load_map(map_name) loads the given map. This method resets the whole simulation to start a new session. map_name can be either a full path or the name of a city in our maps folder, i.e. “Town02” is equivalent to “/Game/Carla/Maps/Town02”. This function returns the newly load world. reload_map() reloads the current map.

world = client.load_world('Town05')

Code example 5: Loading Town05 from client.

Batch commands

We introduced a new method to push to the server a set of vehicle’s commands in batch mode. This is not only more efficient, but also allows for applying a command to every actor in the same tick, e.g. sending the control to every NPC vehicle, or why not, making all the cars jump at the same instant.

vehicles = [x for x in world.get_actors().filter('vehicle.*')]
client.apply_batch([carla.command.ApplyVelocity(x.id, carla.Vector3D(z=5)) for x in vehicles])

batch = [carla.command.SetAutopilot(x.id, False) for x in vehicles]
batch += [carla.command.ApplyVehicleControl(x.id, carla.VehicleControl(throttle=1.0)) for x in vehicles]
client.apply_batch(batch)

Code example 6: Sending a set of vehicle’s control commands in batch.

The following batch commands are available (under carla.command module):

DestroyActor(actor_id)
ApplyVehicleControl(actor_id, control)`
ApplyWalkerControl(actor_id, control)`
ApplyTransform(actor_id, transform)`
ApplyVelocity(actor_id, velocity)`
ApplyAngularVelocity(actor_id, angular_velocity)`
ApplyImpulse(actor_id, impulse)`
SetSimulatePhysics(actor_id, enabled)`
SetAutopilot(actor_id, enabled)`

Code example 7: List of commands supporting batch mode in CARLA.

Support for random streaming port

Now it is possible to control the secondary port used for streaming the sensor data. So far, this port was always set to RPC port + 1, but now it is possible for users to specify this port, and even let the OS choose a random port available if you set the port to 0. The client will automatically connect as this info is sent through the RPC port. These ports can be configured when launching the simulator:

./CarlaUE4.sh -carla-rpc-port=2000 -carla-streaming-port=0

Code example 8: Running CARLA server in a random port for the streaming channel.

Non-sticky vehicle control

We added an attribute to vehicle blueprints to specify whether the applied control is “sticky” or not. By default is set to “True”, i.e., the behavior we always had in previous versions of CARLA

vehicle_blueprint.set_attribute("sticky_control", "False")

Code example 9: Setting a vehicle’s blueprint to behave in a non-sticky way.

However, when “sticky_control” is “False”, the control will be reset every frame to its default (throttle=0, steer=0, brake=0) values. So unless the client sends a control message the vehicle will eventually stop. In the future, we would like to add more realistic relaxation curves for this control.

Importing and exporting maps

In this release, we have simplified the process of creating and ingesting new contents, such as maps and other assets, within CARLA. From now on users won’t have to recompile the CARLA project just to add a new map. Our new importing tools enable users to just add maps on the fly. Please, keep reading to know more.

Importing maps into CARLA

New maps based on FBX and ASAM OpenDRIVE files, such as those created by VectorZero’s RoadRunner software. To this end maps just have to be placed as tar.gz files into the “ExportedMaps” folder within CARLA root folder. Then you can run ImportMaps.sh (for now only on Linux) to patch the map into the project. Then just load that map by invoking it in CARLA by name. An example of this functionality can be seen by downloading our new Town06 and following these instructions:

mv Town06_0.9.4.tar.gz <CARLA_ROOT>/ExportedMaps
cd <CARLA_ROOT>
bash ImportMaps.sh
bash CarlaUE4.sh Town06

Code example 10: Importing a new Town into CARLA.

No rendering mode update

We have continued improving the new No Rendering Mode for this release, enhancing both performance and visual aesthetic aspects. We have significantly improved the framerate and solved the freezing issue when zooming in and out in Map Mode. From the visual perspective, the visualizer looks nicer and more intuitive now. We have also added further road information such as adding stop signs and also made explicit the traffic light affecting the ego-vehicle by applying a glowing effect on the traffic light. Useful right?

town04_2

Figure 1. Views of the new Town06.

Fine control over traffic lights and signs

Now, all the traffic lights belonging to the same intersection are exposed as a group. This simplifies the control logic and allows users to think at the level of traffic intersections.

if vehicle.is_at_traffic_light():
    tl = vehicle.get_traffic_light()
    for x in tl.get_group_traffic_lights():
        x.freeze()
        if x.get_pole_index() == tl.id:
            state = carla.TrafficLightState.Green
        else:
            state = carla.TrafficLightState.Red
        x.set_state(state)

Code example 11: Getting traffic lights group affecting to an actor and change its state.

traffic_lights = world.get_actors().filter('traffic.traffic_light')

for traffic_light in traffic_lights:
    trigger = traffic_light.trigger_volume
    traffic_light.get_transform().transform(trigger.location)

    # Calculate box intersection (rough approximation).
    distance_to_car = trigger.location.distance(vehicle.get_location())
    s = Util.length(trigger.extent) + Util.length(vehicle.bounding_box.extent)
    if distance_to_car <= s:
        # the actor is affected by this traffic light.

Code example 12: Finding the traffic light affecting an actor.

Lane change extension

The Waypoint API has been extended with a set of new functions that provide the information needed to deal with lane changes. These functions are as follows:

  • carla.Waypoint.lane_change: Returns a carla.LaneChange.
  • carla.LaneChange: A Python enum that tells whether traffic rules allow a lane change.
    • 0: None
    • 1: Right
    • 2: Left
    • 3: Both
    • Can be used as a flag e.g.:
      • LaneChange.Right & LaneChange.None => False
      • LaneChange.Right & LaneChange.Left => False
      • LaneChange.Right & LaneChange.Both => True
      • LaneChange.Right & LaneChange.Right => True
  • carla.Waypoint.lane_type: Returns an string that codifies the type of the current lane, i.e.:
  • “driving”,
  • “bidirectional”
  • “shoulder”,
  • “sidewalk”
  • “median”
  • “parking”
  • “none”
  • carla.Waypoint.get_right_lane(): Returns another carla.Waypoint (although the rules allow the change or not) at the closest right neighbor lane. If there is no right lane, it returns None.
  • carla.Waypoint.get_left_lane(): Returns another carla.Waypoint (although the rules allow the change or not) at the closest left neighbor lane. If there is no left lane, it returns None. Notice that if the new waypoint is on a different signed lane_id, it does mean that it is in the opposite direction.

Building on Windows

The Windows build has been highly improved. Now it downloads and installs libpng so you can correctly save images from the PythonAPI, that now compiles like a charm.

If you face some issue while running a client Python script, complaining about missing DLL, you just need to compile (or easily find on the Internet) a fresh x64 zlib.dll, and put it in carla\PythonAPI folder. Sorry for the inconvenience, we’ll try to fix this ASAP!

Remember!
  Make sure you are using Python3.7 x64
  Make sure you have Git, Make, CMake, Python in your PATH
  Compile using Visual Studio x64 Native Tools Command Prompt, not cmd!
  Update Visual studio from time to time
  Remember to download the assets

New Town: Town06 (codename Caladan)

As usual in Carla, we always explore new ways to test your agents and add variety to our maps. We created Town06 to test the type of maneuvers referred to as “Michigan Left”. These layouts involve on-and-off connections ramps between two highways and dedicated turning lanes. Is your agent able to perform a Michigan Left?

town04_2 town04_2

Figure 1. Views of the new Town06.

Performance benchmarking script

Now you can determine what to expect from CARLA in terms of computational performance under different platforms thanks to the performance_benchmark.py script. This script generates a summary of the server performance in terms of FPS (frames per second) for different sensor configurations, maps and weather conditions. You can see an example of this information below:

Sensors Town Weather Samples Mean fps Std fps
1. cam-300x200 /Game/Carla/Maps/Town01 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 57.89 24.15
1. cam-300x200 /Game/Carla/Maps/Town01 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 66.87 22.00
1. cam-300x200 /Game/Carla/Maps/Town01 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 60.61 21.87
1. cam-300x200 /Game/Carla/Maps/Town02 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 91.75 26.35
1. cam-300x200 /Game/Carla/Maps/Town02 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 94.62 25.00
1. cam-300x200 /Game/Carla/Maps/Town02 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 95.76 26.53
1. cam-300x200 /Game/Carla/Maps/Town03 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 95.86 32.87
1. cam-300x200 /Game/Carla/Maps/Town03 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 100.13 37.76
1. cam-300x200 /Game/Carla/Maps/Town03 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 104.10 34.15
1. cam-300x200 /Game/Carla/Maps/Town04 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 134.98 32.31
1. cam-300x200 /Game/Carla/Maps/Town04 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 141.26 31.48
1. cam-300x200 /Game/Carla/Maps/Town04 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 133.14 39.00
1. cam-300x200 /Game/Carla/Maps/Town05 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 73.74 17.96
1. cam-300x200 /Game/Carla/Maps/Town05 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 79.93 18.29
1. cam-300x200 /Game/Carla/Maps/Town05 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 72.38 24.20
2. cam-800x600 /Game/Carla/Maps/Town01 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 49.27 16.68
2. cam-800x600 /Game/Carla/Maps/Town01 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 51.47 20.07
2. cam-800x600 /Game/Carla/Maps/Town01 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 53.93 17.65
2. cam-800x600 /Game/Carla/Maps/Town02 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 70.71 19.17
2. cam-800x600 /Game/Carla/Maps/Town02 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 70.03 20.04
2. cam-800x600 /Game/Carla/Maps/Town02 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 69.65 19.17
2. cam-800x600 /Game/Carla/Maps/Town03 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 79.25 28.94
2. cam-800x600 /Game/Carla/Maps/Town03 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 76.49 28.77
2. cam-800x600 /Game/Carla/Maps/Town03 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 75.99 31.54
2. cam-800x600 /Game/Carla/Maps/Town04 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 112.54 28.37
2. cam-800x600 /Game/Carla/Maps/Town04 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 112.12 33.32
2. cam-800x600 /Game/Carla/Maps/Town04 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 123.42 26.23
2. cam-800x600 /Game/Carla/Maps/Town05 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 54.81 17.86
2. cam-800x600 /Game/Carla/Maps/Town05 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 58.98 16.15
2. cam-800x600 /Game/Carla/Maps/Town05 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 60.43 16.42
3. cam-1900x1080 /Game/Carla/Maps/Town01 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 39.64 14.79
3. cam-1900x1080 /Game/Carla/Maps/Town01 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 40.91 15.16
3. cam-1900x1080 /Game/Carla/Maps/Town01 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 41.37 16.47
3. cam-1900x1080 /Game/Carla/Maps/Town02 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 54.05 15.64
3. cam-1900x1080 /Game/Carla/Maps/Town02 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 57.32 15.29
3. cam-1900x1080 /Game/Carla/Maps/Town02 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 54.12 12.96
3. cam-1900x1080 /Game/Carla/Maps/Town03 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 61.30 21.94
3. cam-1900x1080 /Game/Carla/Maps/Town03 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 64.28 22.77
3. cam-1900x1080 /Game/Carla/Maps/Town03 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 63.37 20.76
3. cam-1900x1080 /Game/Carla/Maps/Town04 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 80.69 20.13
3. cam-1900x1080 /Game/Carla/Maps/Town04 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 84.10 20.93
3. cam-1900x1080 /Game/Carla/Maps/Town04 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 82.19 19.15
3. cam-1900x1080 /Game/Carla/Maps/Town05 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 47.33 12.34
3. cam-1900x1080 /Game/Carla/Maps/Town05 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 45.01 14.50
3. cam-1900x1080 /Game/Carla/Maps/Town05 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 47.93 12.58
4. cam-300x200 cam-300x200 /Game/Carla/Maps/Town01 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 34.14 13.10
4. cam-300x200 cam-300x200 /Game/Carla/Maps/Town01 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 35.94 15.76
4. cam-300x200 cam-300x200 /Game/Carla/Maps/Town01 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 35.87 12.46
4. cam-300x200 cam-300x200 /Game/Carla/Maps/Town02 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 54.38 16.08
4. cam-300x200 cam-300x200 /Game/Carla/Maps/Town02 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 53.78 16.84
4. cam-300x200 cam-300x200 /Game/Carla/Maps/Town02 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 55.51 15.93
4. cam-300x200 cam-300x200 /Game/Carla/Maps/Town03 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 56.11 25.36
4. cam-300x200 cam-300x200 /Game/Carla/Maps/Town03 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 60.24 26.24
4. cam-300x200 cam-300x200 /Game/Carla/Maps/Town03 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 61.07 26.86
4. cam-300x200 cam-300x200 /Game/Carla/Maps/Town04 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 87.22 19.07
4. cam-300x200 cam-300x200 /Game/Carla/Maps/Town04 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 85.30 24.16
4. cam-300x200 cam-300x200 /Game/Carla/Maps/Town04 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 94.08 19.66
4. cam-300x200 cam-300x200 /Game/Carla/Maps/Town05 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 43.23 11.53
4. cam-300x200 cam-300x200 /Game/Carla/Maps/Town05 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 40.25 13.44
4. cam-300x200 cam-300x200 /Game/Carla/Maps/Town05 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 41.20 11.20
5. LIDAR /Game/Carla/Maps/Town01 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 162.40 65.25
5. LIDAR /Game/Carla/Maps/Town01 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 148.50 51.77
5. LIDAR /Game/Carla/Maps/Town01 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 151.75 49.49
5. LIDAR /Game/Carla/Maps/Town02 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 420.15 434.85
5. LIDAR /Game/Carla/Maps/Town02 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 1205.93 2734.93
5. LIDAR /Game/Carla/Maps/Town02 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 270.26 115.43
5. LIDAR /Game/Carla/Maps/Town03 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 149.28 88.60
5. LIDAR /Game/Carla/Maps/Town03 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 183.08 62.25
5. LIDAR /Game/Carla/Maps/Town03 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 182.54 61.77
5. LIDAR /Game/Carla/Maps/Town04 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 214.12 108.30
5. LIDAR /Game/Carla/Maps/Town04 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 166.44 74.77
5. LIDAR /Game/Carla/Maps/Town04 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 240.93 90.11
5. LIDAR /Game/Carla/Maps/Town05 WeatherParameters(cloudyness=15, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 234.66 93.94
5. LIDAR /Game/Carla/Maps/Town05 WeatherParameters(cloudyness=80, precipitation=0, precipitation_deposits=0, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=75) 150 224.18 92.64
5. LIDAR /Game/Carla/Maps/Town05 WeatherParameters(cloudyness=90, precipitation=15, precipitation_deposits=50, wind_intensity=0.35, sun_azimuth_angle=0, sun_altitude_angle=15) 150 212.34 103.62

Table: Results for Epics quality and variable framerate. CPU Intel(R) Core(TM) i7-5960X CPU @ 3.00GHz 6. 62.73 GB RAM memory. GPU TITAN Xp .

As usual, if you find any issues or have suggestions that can be added, please do not hesitate toshare it with the community at our GitHub or Discord chat. For the full list of methods available take a look at the Python API Reference.


Full list of changes

  • Added recording and playback functionality
  • Added synchronous mode, simulator waits until a client sends a “tick” cue, client.tick()
  • Allow changing map from client-side, added client.load_map(name), client.reload_map(), and client.get_available_maps()
  • Added scripts and tools to import maps directly from .fbx and .xodr files into the simulator
  • Exposed minimum physics control parameters for vehicles’ engine and wheels
  • Allow controlling multiple actors in “batch mode”
  • New Town06, featuring a “Michigan left” intersection including:
  • Connection ramp between two highways
  • Incorporation to a highway requiring changing several lanes to take another exit
  • Junctions supporting different scenarios
  • New traffic signs assets: one-way, no-turn, more speed limits, do not enter, arrow floors, Michigan left, and lane end
  • New pedestrian texture to add more variations
  • New road PBR material
  • Extended the waypoint API with lane_change, lane_type, get_right_lane() and get_left_lane()
  • Added world settings for changing no-rendering mode and synchronous mode at run-time
  • Added methods to acquire a traffic light’s pole index and all traffic lights in its group
  • Added performance benchmark script to measure the simulator’s rendering performance
  • Added manual_control_steeringwheel.py to control agents using Logitech G29 steering wheels (and maybe others)
  • Added movable props present in the map (e.g. chairs and tables) as actors so they can be controlled from Python
  • Added recording and playback bindings to manual_control.py script
  • Removed world.map_name from API, use world.get_map().name instead
  • Refactored no_rendering_mode.py to improve performance and interface
  • Several improvements to the build system for Windows
  • Expose traffic sign’s trigger volumes on Python API
  • Improved export/import map tools
  • Simplify Dockerfile halving Carla Docker image size
  • Episodes have now a random unique id to avoid collisions between runs
  • Reduced overhead of many RPC calls by sending only actor IDs (instead of serializing all the actor attributes every time)
  • Added priority system for vehicle control input (internal, not exposed in API)
  • Removed “Example.CarlaSettings.ini”, you can still use it, but it’s no longer necessary
  • Improved time-out related error messages
  • Fixed Town01 placed 38 meters above the zero
  • Fixed parsing of OpenDRIVE geo-reference exported by RoadRunner
  • Fixed issue of retrieving an empty list when calling world.get_actors() right after creating the world
  • Fixed a few synchronization issues related to changing the world at runtime
  • Fixed traffic light when it gets illuminated by the hero vehicle in no_rendering_mode.py
  • Fixed manual_control.py and no_rendering_mode.py to prevent crashes when used in “no rendering mode”
  • Fixed traffic signs having the trigger box rotated
  • Fixed female walk animation
  • Fixed BP_MultipleFloor, tweaked offset in BaseFloor to adjust meshes between them
  • Fixed static objects present in the map were marked as “movable”